Adds support for ADF7023 sub-GHz radio from Analog Devices and RL78 series MCU from Renesas.

This example platform for this port is the EVAL-ADF7XXXMB4Z w/ radio
daughter cards:

    http://www.analog.com/en/evaluation/eval-adf7023/eb.html

See the platform readme for usage and platform information:

    https://github.com/contiki-os/contiki/tree/master/platform/eval-adf7xxxmb4z/readme.md

All files provided by Analog Devices for this port are released under
the same license as Contiki and copyright Analog Devices Inc. per
agreement between Redwire Consulting, LLC and Analog Devices Inc. (SOW 08122013)
ico
Ian Martin 2014-01-04 18:56:51 -05:00
parent e90af44ca7
commit 174d4dd80c
34 changed files with 11483 additions and 425 deletions

4
.gitignore vendored
View File

@ -84,3 +84,7 @@ contiki-cc2530dk.lib
#regression tests artifacts
*.testlog
# rl78 build artifacts
*.eval-adf7xxxmb4z
*.eval-adf7xxxmb4z.srec

View File

@ -16,12 +16,17 @@ before_script:
https://raw.github.com/wiki/malvira/libmc1322x/files/arm-2008q3-66-arm-none-eabi-i686-pc-linux-gnu.tar.bz2 \
| tar xjf - -C /tmp/ && sudo cp -f -r /tmp/arm-2008q3/* /usr/ && rm -rf /tmp/arm-2008q3 && arm-none-eabi-gcc --version || true"
## Install RL78 GCC chain (following the instructions in platform/eval-adf7xxxmb4z/README.md)
- "sudo apt-get install git make gcc libc-dev multiarch-support libncurses5:i386 zlib1g:i386"
- "wget https://dl.dropboxusercontent.com/u/60522916/gnurl78-v13.02-elf_1-2_i386.deb"
- "sudo dpkg -i gnurl78*.deb"
## Install SDCC from a purpose-built bundle
- "[ ${BUILD_ARCH:-0} = 8051 ] && curl -s \
https://raw.github.com/wiki/g-oikonomou/contiki-sensinode/files/sdcc.tar.gz \
| tar xzf - -C /tmp/ && sudo cp -f -r /tmp/sdcc/* /usr/local/ && rm -rf /tmp/sdcc && sdcc --version || true"
- "[ ${BUILD_ARCH:-0} = 8051 ] && sudo apt-get -qq install srecord || true"
## Clone and build cc65 when testing 6502 ports
- "[ ${BUILD_ARCH:-0} = 6502 ] && git clone \
https://github.com/oliverschmidt/cc65 /tmp/cc65 && \

View File

@ -1,50 +1,66 @@
/***************************************************************************//**
* @file Communication.c
* @brief Implementation of the Communication Driver for RL78G14 processor.
* @author DBogdan (dragos.bogdan@analog.com)
********************************************************************************
* Copyright 2012(c) Analog Devices, Inc.
*
/*
* Copyright (c) 2014, Analog Devices, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* - Redistributions of source code must retain the above copyright
* modification, are permitted provided that the following conditions
* are met:
* 1. 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
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
* - The use of this software may or may not infringe the patent rights
* of one or more patent holders. This license does not release you
* from the requirement that you obtain separate licenses from these
* patent holders to use this software.
* - Use of the software either in source or binary form, must be run
* on or directly connected to an Analog Devices Inc. component.
*
* THIS SOFTWARE IS PROVIDED BY ANALOG DEVICES "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, NON-INFRINGEMENT,
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
* IN NO EVENT SHALL ANALOG DEVICES BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, INTELLECTUAL PROPERTY RIGHTS, 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.
*
********************************************************************************
* SVN Revision: $WCREV$
*******************************************************************************/
* 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 HOLDER 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 Dragos Bogdan <Dragos.Bogdan@Analog.com>, Ian Martin <martini@redwirellc.com>
*/
/******************************************************************************/
/***************************** Include Files **********************************/
/******************************************************************************/
#include <stdint.h>
#include "rl78.h"
#include "Communication.h" /* Communication definitions */
#include "RDKRL78G14.h" /* RDKRL78G14 definitions */
#ifndef NOP
#define NOP asm ("nop")
#endif
/* Enable interrupts: */
#ifndef EI
#ifdef __GNUC__
#define EI asm ("ei");
#else
#define EI __enable_interrupt();
#endif
#endif
#undef BIT
#define BIT(n) (1 << (n))
#define CLK_SCALER (0x4)
#define SCALED_CLK (f_CLK / (1 << CLK_SCALER))
#define BITBANG_SPI 1
char IICA0_Flag;
@ -57,8 +73,7 @@ char IICA0_Flag;
*
* @return None.
*******************************************************************************/
#pragma vector = INTIICA0_vect
__interrupt static void
/*__interrupt */ static void
IICA0_Interrupt(void)
{
IICA0_Flag = 1;
@ -87,25 +102,40 @@ IICA0_Interrupt(void)
* -1 - if initialization was unsuccessful.
*******************************************************************************/
char
SPI_Init(char lsbFirst,
SPI_Init(enum CSI_Bus bus,
char lsbFirst,
long clockFreq,
char clockPol,
char clockEdg)
{
long mckFreq = 32000000;
#if BITBANG_SPI
PIOR5 = 1; /* Move SPI/I2C/UART functions from Port 0 pins 2-4 to Port 8. */
/* Configure SCLK as an output. */
PM0 &= ~BIT(4);
POM0 &= ~BIT(4);
/* Configure MOSI as an output: */
PM0 &= ~BIT(2);
POM0 &= ~BIT(2);
PMC0 &= ~BIT(2);
/* Configure MISO as an input: */
PM0 |= BIT(3);
PMC0 &= ~BIT(3);
#else
char sdrValue = 0;
char delay = 0;
uint16_t scr;
uint8_t shift;
/* Configure the CS pins. */
PMOD1_CS_OUT;
PMOD1_CS_HIGH;
PMOD2_CS_OUT;
PMOD2_CS_HIGH;
ST7579_CS_OUT;
ST7579_CS_HIGH;
PIOR5 = 0; /* Keep SPI functions on Port 0 pins 2-4. */
/* Enable input clock supply. */
SAU1EN = 1;
if(bus <= CSI11) {
SAU0EN = 1;
} else { SAU1EN = 1;
}
/* After setting the SAUmEN bit to 1, be sure to set serial clock select
register m (SPSm) after 4 or more fCLK clocks have elapsed. */
@ -115,36 +145,195 @@ SPI_Init(char lsbFirst,
NOP;
/* Select the fCLK as input clock. */
SPS1 = 0x0000;
if(bus <= CSI11) {
SPS0 = (CLK_SCALER << 4) | CLK_SCALER; /* TODO: kludge */
} else { SPS1 = (CLK_SCALER << 4) | CLK_SCALER; /* TODO: kludge */
}
/* Select the CSI operation mode. */
SMR11 = 0x0020;
switch(bus) {
case CSI00: SMR00 = 0x0020;
break;
case CSI01: SMR01 = 0x0020;
break;
case CSI10: SMR02 = 0x0020;
break;
case CSI11: SMR03 = 0x0020;
break;
case CSI20: SMR10 = 0x0020;
break;
case CSI21: SMR11 = 0x0020;
break;
case CSI30: SMR12 = 0x0020;
break;
case CSI31: SMR13 = 0x0020;
break;
}
clockPol = 1 - clockPol;
SCR11 = (clockEdg << 13) |
scr = (clockEdg << 13) |
(clockPol << 12) |
0xC000 | /* Operation mode: Transmission/reception. */
0x0007; /* 8-bit data length. */
switch(bus) {
case CSI00: SCR00 = scr;
break;
case CSI01: SCR01 = scr;
break;
case CSI10: SCR02 = scr;
break;
case CSI11: SCR03 = scr;
break;
case CSI20: SCR10 = scr;
break;
case CSI21: SCR11 = scr;
break;
case CSI30: SCR12 = scr;
break;
case CSI31: SCR13 = scr;
break;
}
/* clockFreq = mckFreq / (sdrValue * 2 + 2) */
sdrValue = mckFreq / (2 * clockFreq) - 1;
SDR11 = sdrValue << 9;
sdrValue = SCALED_CLK / (2 * clockFreq) - 1;
sdrValue <<= 9;
switch(bus) {
case CSI00: SDR00 = sdrValue;
break;
case CSI01: SDR01 = sdrValue;
break;
case CSI10: SDR02 = sdrValue;
break;
case CSI11: SDR03 = sdrValue;
break;
case CSI20: SDR10 = sdrValue;
break;
case CSI21: SDR11 = sdrValue;
break;
case CSI30: SDR12 = sdrValue;
break;
case CSI31: SDR13 = sdrValue;
break;
}
/* Set the clock and data initial level. */
clockPol = 1 - clockPol;
SO1 &= ~0x0202;
SO1 |= (clockPol << 9) |
(clockPol << 1);
shift = bus & 0x3;
if(bus <= CSI11) {
SO0 &= ~(0x0101 << shift);
SO0 |= ((clockPol << 8) | clockPol) << shift;
} else {
SO1 &= ~(0x0101 << shift);
SO1 |= ((clockPol << 8) | clockPol) << shift;
}
/* Enable output for serial communication operation. */
SOE1 |= 0x0002;
switch(bus) {
case CSI00: SOE0 |= BIT(0);
break;
case CSI01: SOE0 |= BIT(1);
break;
case CSI10: SOE0 |= BIT(2);
break;
case CSI11: SOE0 |= BIT(3);
break;
case CSI20: SOE1 |= BIT(0);
break;
case CSI21: SOE1 |= BIT(1);
break;
case CSI30: SOE1 |= BIT(2);
break;
case CSI31: SOE1 |= BIT(3);
break;
}
/* Configure the MISO pin as input. */
PM7 |= 0x02;
switch(bus) {
case CSI00:
/* SO00 output: */
P1 |= BIT(2);
PM1 &= ~BIT(2);
/* Configure SCLK and MOSI pins as output. */
P7 |= 0x05;
PM7 &= ~0x05;
/* SI00 input: */
PM1 |= BIT(1);
/* SCK00N output: */
P1 |= BIT(0);
PM1 &= ~BIT(0);
break;
case CSI01:
/* SO01 output: */
P7 |= BIT(3);
PM7 &= ~BIT(3);
/* SI01 input: */
PM7 |= BIT(4);
/* SCK01 output: */
P7 |= BIT(5);
PM7 &= ~BIT(5);
break;
case CSI10:
PMC0 &= ~BIT(2); /* Disable analog input on SO10. */
/* SO10 output: */
P0 |= BIT(2);
PM0 &= ~BIT(2);
/* SI10 input: */
PM0 |= BIT(3);
/* SCK10N output: */
P0 |= BIT(4);
PM0 &= ~BIT(4);
break;
case CSI11:
/* SO11 output: */
P5 |= BIT(1);
PM5 &= ~BIT(1);
/* SI11 input: */
PM5 |= BIT(0);
/* SCK11 output: */
P3 |= BIT(0);
PM3 &= ~BIT(0);
break;
case CSI20:
/* SO20 output: */
P1 |= BIT(3);
PM1 &= ~BIT(3);
/* SI20 input: */
PM1 |= BIT(4);
/* SCK20 output: */
P1 |= BIT(5);
PM1 &= ~BIT(5);
break;
case CSI21:
/* SO21 output: */
P7 |= BIT(2);
PM7 &= ~BIT(2);
/* SI21 input: */
PM7 |= BIT(1);
/* SCK21 output: */
P7 |= BIT(0);
PM7 &= ~BIT(0);
break;
case CSI30:
/* TODO: not supported */
break;
case CSI31:
/* TODO: not supported */
break;
}
/* Wait for the changes to take place. */
for(delay = 0; delay < 50; delay++) {
@ -152,7 +341,44 @@ SPI_Init(char lsbFirst,
}
/* Set the SEmn bit to 1 and enter the communication wait status */
SS1 |= 0x0002;
switch(bus) {
case CSI00: SS0 = BIT(0);
break;
case CSI01: SS0 = BIT(1);
break;
case CSI10: SS0 = BIT(2);
break;
case CSI11: SS0 = BIT(3);
break;
case CSI20: SS1 = BIT(0);
break;
case CSI21: SS1 = BIT(1);
break;
case CSI30: SS1 = BIT(2);
break;
case CSI31: SS1 = BIT(3);
break;
}
/* Sanity check: */
if(bus == CSI10) {
/* MOSI: */
PIOR5 = 0;
PMC02 = 0;
PM02 = 0;
P02 = 1;
/* MISO: */
PIOR5 = 0;
PMC03 = 0;
PM03 = 1;
/* SCLK: */
PIOR5 = 0;
PM04 = 0;
P04 = 1;
}
#endif
return 0;
}
@ -165,8 +391,10 @@ SPI_Init(char lsbFirst,
*
* @return Number of written bytes.
*******************************************************************************/
#if 0
char
SPI_Write(char slaveDeviceId,
SPI_Write(enum CSI_Bus bus,
char slaveDeviceId,
unsigned char *data,
char bytesNumber)
{
@ -175,43 +403,84 @@ SPI_Write(char slaveDeviceId,
unsigned short originalSCR = 0;
unsigned short originalSO1 = 0;
if(slaveDeviceId == 1) {
PMOD1_CS_LOW;
}
if(slaveDeviceId == 2) {
PMOD2_CS_LOW;
}
if(slaveDeviceId == 3) {
ST1 |= 0x0002;
originalSO1 = SO1;
originalSCR = SCR11;
SO1 &= ~0x0202;
SCR11 &= ~0x3000;
SS1 |= 0x0002;
ST7579_CS_LOW;
volatile uint8_t *sio;
volatile uint16_t *ssr;
switch(bus) {
default:
case CSI00: sio = &SIO00;
ssr = &SSR00;
break;
case CSI01: sio = &SIO01;
ssr = &SSR01;
break;
case CSI10: sio = &SIO10;
ssr = &SSR02;
break;
case CSI11: sio = &SIO11;
ssr = &SSR03;
break;
case CSI20: sio = &SIO20;
ssr = &SSR10;
break;
case CSI21: sio = &SIO21;
ssr = &SSR11;
break;
case CSI30: sio = &SIO30;
ssr = &SSR12;
break;
case CSI31: sio = &SIO31;
ssr = &SSR13;
break;
}
for(byte = 0; byte < bytesNumber; byte++) {
SIO21 = data[byte];
*sio = data[byte];
NOP;
while(SSR11 & 0x0040) ;
read = SIO21;
}
if(slaveDeviceId == 1) {
PMOD1_CS_HIGH;
}
if(slaveDeviceId == 2) {
PMOD2_CS_HIGH;
}
if(slaveDeviceId == 3) {
ST7579_CS_HIGH;
ST1 |= 0x0002;
SO1 = originalSO1;
SCR11 = originalSCR;
SS1 |= 0x0002;
while(*ssr & 0x0040) ;
read = *sio;
}
return bytesNumber;
}
#endif
#if BITBANG_SPI
#define sclk_low() (P0 &= ~BIT(4))
#define sclk_high() (P0 |= BIT(4))
#define mosi_low() (P0 &= ~BIT(2))
#define mosi_high() (P0 |= BIT(2))
#define read_miso() (P0bits.bit3)
static unsigned char
spi_byte_exchange(unsigned char tx)
{
unsigned char rx = 0, n = 0;
sclk_low();
for(n = 0; n < 8; n++) {
if(tx & 0x80) {
mosi_high();
} else { mosi_low();
}
/* The slave samples MOSI at the rising-edge of SCLK. */
sclk_high();
rx <<= 1;
rx |= read_miso();
tx <<= 1;
/* The slave changes the value of MISO at the falling-edge of SCLK. */
sclk_low();
}
return rx;
}
#endif
/***************************************************************************//**
* @brief Reads data from SPI.
*
@ -223,48 +492,64 @@ SPI_Write(char slaveDeviceId,
* @return Number of read bytes.
*******************************************************************************/
char
SPI_Read(char slaveDeviceId,
SPI_Read(enum CSI_Bus bus,
char slaveDeviceId,
unsigned char *data,
char bytesNumber)
{
#if BITBANG_SPI
unsigned char n = 0;
for(n = 0; n < bytesNumber; n++) {
data[n] = spi_byte_exchange(data[n]);
}
#else
char byte = 0;
unsigned short originalSCR = 0;
unsigned short originalSO1 = 0;
if(slaveDeviceId == 1) {
PMOD1_CS_LOW;
}
if(slaveDeviceId == 2) {
PMOD2_CS_LOW;
}
if(slaveDeviceId == 3) {
ST1 |= 0x0002;
originalSO1 = SO1;
originalSCR = SCR11;
SO1 &= ~0x0202;
SCR11 &= ~0x3000;
SS1 |= 0x0002;
ST7579_CS_LOW;
volatile uint8_t *sio;
volatile uint16_t *ssr;
char dummy;
switch(bus) {
default:
case CSI00: sio = &SIO00;
ssr = &SSR00;
break;
case CSI01: sio = &SIO01;
ssr = &SSR01;
break;
case CSI10: sio = &SIO10;
ssr = &SSR02;
break;
case CSI11: sio = &SIO11;
ssr = &SSR03;
break;
case CSI20: sio = &SIO20;
ssr = &SSR10;
break;
case CSI21: sio = &SIO21;
ssr = &SSR11;
break;
case CSI30: sio = &SIO30;
ssr = &SSR12;
break;
case CSI31: sio = &SIO31;
ssr = &SSR13;
break;
}
/* Flush the receive buffer: */
while(*ssr & 0x0020) dummy = *sio;
(void)dummy;
for(byte = 0; byte < bytesNumber; byte++) {
SIO21 = data[byte];
*sio = data[byte];
NOP;
while(SSR11 & 0x0040) ;
data[byte] = SIO21;
}
if(slaveDeviceId == 1) {
PMOD1_CS_HIGH;
}
if(slaveDeviceId == 2) {
PMOD2_CS_HIGH;
}
if(slaveDeviceId == 3) {
ST7579_CS_HIGH;
ST1 |= 0x0002;
SO1 = originalSO1;
SCR11 = originalSCR;
SS1 |= 0x0002;
while(*ssr & 0x0040) ;
data[byte] = *sio;
}
#endif
return bytesNumber;
}
@ -284,6 +569,8 @@ I2C_Init(long clockFreq)
unsigned char wlValue = 0;
unsigned char whValue = 0;
(void)IICA0_Interrupt; /* Prevent an unused-function warning. */
/* Enable interrupts */
EI;

View File

@ -1,58 +1,43 @@
/***************************************************************************//**
* @file Communication.h
* @brief Header file of the Communication Driver for RL78G14 processor.
* @author DBogdan (dragos.bogdan@analog.com)
********************************************************************************
* Copyright 2012(c) Analog Devices, Inc.
*
/*
* Copyright (c) 2014, Analog Devices, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* - Redistributions of source code must retain the above copyright
* modification, are permitted provided that the following conditions
* are met:
* 1. 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
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
* - The use of this software may or may not infringe the patent rights
* of one or more patent holders. This license does not release you
* from the requirement that you obtain separate licenses from these
* patent holders to use this software.
* - Use of the software either in source or binary form, must be run
* on or directly connected to an Analog Devices Inc. component.
*
* THIS SOFTWARE IS PROVIDED BY ANALOG DEVICES "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, NON-INFRINGEMENT,
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
* IN NO EVENT SHALL ANALOG DEVICES BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, INTELLECTUAL PROPERTY RIGHTS, 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.
*
********************************************************************************
* SVN Revision: $WCREV$
*******************************************************************************/
* 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 HOLDER 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 Dragos Bogdan <Dragos.Bogdan@Analog.com>
*/
#ifndef __COMMUNICATION_H__
#define __COMMUNICATION_H__
/******************************************************************************/
/***************************** Include Files **********************************/
/******************************************************************************/
#include "RDKRL78G14.h"
/******************************************************************************/
/*************************** Macros Definitions *******************************/
/******************************************************************************/
#define SPI_CS_PIN_OUT PMOD1_CS_OUT
#define SPI_CS_LOW PMOD1_CS_LOW
#define SPI_CS_HIGH PMOD1_CS_HIGH
#define SPI_MISO PMOD1_MISO
#define GPIO1_PIN_OUT PMOD1_GPIO1_PIN_OUT
@ -75,19 +60,33 @@
/************************ Functions Declarations ******************************/
/******************************************************************************/
enum CSI_Bus {
CSI00,
CSI01,
CSI10,
CSI11,
CSI20,
CSI21,
CSI30,
CSI31,
};
/*! Initializes the SPI communication peripheral. */
char SPI_Init(char lsbFirst,
char SPI_Init(enum CSI_Bus bus,
char lsbFirst,
long clockFreq,
char clockPol,
char clockEdg);
/*! Writes data to SPI. */
char SPI_Write(char slaveDeviceId,
char SPI_Write(enum CSI_Bus bus,
char slaveDeviceId,
unsigned char *data,
char bytesNumber);
/*! Reads data from SPI. */
char SPI_Read(char slaveDeviceId,
char SPI_Read(enum CSI_Bus bus,
char slaveDeviceId,
unsigned char *data,
char bytesNumber);

190
cpu/rl78/Makefile.rl78 Executable file
View File

@ -0,0 +1,190 @@
# Copyright (c) 2014, Analog Devices, Inc.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. 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.
#
# 3. Neither the name of the copyright holder nor the names of its
# contributors may be used to endorse or promote products derived
# from this software without specific prior written permission.
#
# 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 HOLDER 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: Ian Martin <martini@redwirellc.com>
CONTIKI_CPU=$(CONTIKI)/cpu/rl78
### Compiler definitions
ifdef IAR
# Use IAR compiler.
# Default code and data models (n = near, f = far):
CODE_MODEL ?= n
DATA_MODEL ?= n
DEVICE ?= r5f100ll
# According to "rl78/config/devices/RL78 - G13/r5f100ll.menu", the R5F100LLA has core 1.
CORE ?= 1
# Default library configuration (n = normal, f = full):
LIB_CONFIG ?= n
IAR_PATH ?= C:\\Program\ Files\\IAR\ Systems\\Embedded\ Workbench\ 6.5\\rl78
CC = $(IAR_PATH)\\bin\\iccrl78
LD = $(IAR_PATH)\\bin\\xlink
AR = $(IAR_PATH)\\bin\\xar
CFLAGS += --silent
CFLAGS += --debug
CFLAGS += --core rl78_$(CORE)
CFLAGS += --code_model $(CODE_MODEL)
CFLAGS += --data_model $(DATA_MODEL)
CFLAGS += -I$(IAR_PATH)\\lib
LDFLAGS += -S
LDFLAGS += -D_NEAR_CONST_LOCATION=0
LDFLAGS += -D_NEAR_CONST_LOCATION_START=03000
LDFLAGS += -D_NEAR_CONST_LOCATION_END=07EFF
LDFLAGS += -D_NEAR_HEAP_SIZE=400
LDFLAGS += -D_FAR_HEAP_SIZE=4000
LDFLAGS += -D_CSTACK_SIZE=400
LDFLAGS += -s __program_start
LDFLAGS += -f $(IAR_PATH)\\config\\lnk$(DEVICE).xcl
LDFLAGS += -Felf
AROPTS ?= -S
TARGET_LIBFILES += $(IAR_PATH)\\lib\\dlrl78$(CODE_MODEL)$(DATA_MODEL)$(CORE)$(LIB_CONFIG).r87
CUSTOM_RULE_C_TO_O = 1
%.o: %.c
$(TRACE_CC)
$(Q)$(CC) $(CFLAGS) $< -o $@
CUSTOM_RULE_C_TO_OBJECTDIR_O = 1
$(OBJECTDIR)/%.o: %.c | $(OBJECTDIR)
$(TRACE_CC)
$(Q)$(CC) $(CFLAGS) $< --dependencies=m $(@:.o=.P) -o $@
CUSTOM_RULE_C_TO_CO = 1
%.co: %.c
$(TRACE_CC)
$(Q)$(CC) $(CFLAGS) -DAUTOSTART_ENABLE $< -o $@
# The only reason we use a custom link rule here is to simultaneously produce an srec file.
CUSTOM_RULE_LINK = 1
%.$(TARGET) %.$(TARGET).srec: %.co $(PROJECT_OBJECTFILES) $(PROJECT_LIBRARIES) contiki-$(TARGET).a
$(TRACE_LD)
$(Q)$(LD) $(LDFLAGS) $(TARGET_STARTFILES) ${filter-out %.a,$^} \
${filter %.a,$^} $(TARGET_LIBFILES) -o $@ -Omotorola=$@.srec
else
# Use the GNU RL78 toolchain.
ifndef CROSS_COMPILE
ifeq ($(shell which rl78-elf-gcc),)
# The RL78 toolchain is not in the path. Try finding it in /usr/share:
CROSS_COMPILE := $(shell echo /usr/share/*rl78*/bin | tail -1)/rl78-elf-
else
# The RL78 toolchain is in the path. Use it directly:
CROSS_COMPILE := rl78-elf-
endif
endif
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
ifdef WERROR
CFLAGSWERROR ?= -Werror -pedantic -std=c99 -Werror
endif
CFLAGSNO ?= -Wall -g $(CFLAGSWERROR)
CFLAGS += $(CFLAGSNO) -O
CFLAGS += -mmul=g13
CFLAGS += -Os -ggdb -ffunction-sections -fdata-sections
CFLAGS += -fno-strict-aliasing
# Enable override of write() function:
CFLAGS += -fno-builtin
LDFLAGS += -fno-builtin
LDFLAGS += -Wl,--gc-sections -T $(CONTIKI_CPU)/R5F100xL.ld -nostartfiles
ASFLAGS += -c
# C runtime assembly:
CONTIKI_ASMFILES += crt0.S
CONTIKI_OBJECTFILES += $(OBJECTDIR)/crt0.o
endif
ifdef SERIAL_ID
CFLAGS += -DSERIAL_ID='$(SERIAL_ID)'
endif
### CPU-dependent directories
CONTIKI_CPU_DIRS += .
CONTIKI_CPU_DIRS += sys
CONTIKI_CPU_DIRS += adf7023
### CPU-dependent source files
CONTIKI_SOURCEFILES += uart0.c
CONTIKI_SOURCEFILES += clock.c
CONTIKI_SOURCEFILES += write.c
CONTIKI_SOURCEFILES += Communication.c
CONTIKI_SOURCEFILES += ADF7023.c
CONTIKI_SOURCEFILES += assert.c
CONTIKI_SOURCEFILES += slip-arch.c
CONTIKI_SOURCEFILES += contiki-uart.c
CONTIKI_SOURCEFILES += watchdog.c
### Compilation rules
%.so: $(OBJECTDIR)/%.o
$(LD) -shared -o $@ $^
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
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}
%.srec: %
$(OBJCOPY) -O srec $^ $@
%.lst: %.elf
$(OBJDUMP) -DS $^ > $@
%.lst: %
$(OBJDUMP) -DS $^ > $@

View File

@ -29,6 +29,9 @@ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/**
* \author DJ Delorie <dj@redhat.com>, Ian Martin <martini@redwirellc.com>
*/
/* Default linker script, for normal executables */
OUTPUT_ARCH(rl78)
@ -37,13 +40,14 @@ ENTRY(_start)
/* Do we need any of these for elf?
__DYNAMIC = 0; */
/* This is for an RL78/G13, 64k flash, 4k ram */
/* This is for an R5F100xL, 512k flash, 32k ram, 8k data flash */
MEMORY {
VEC (r) : ORIGIN = 0x00000, LENGTH = 0x00002
IVEC (r) : ORIGIN = 0x00004, LENGTH = 0x0007c
OPT (r) : ORIGIN = 0x000c0, LENGTH = 0x00004
ROM (r) : ORIGIN = 0x000d8, LENGTH = 0x0ff28
RAM (w) : ORIGIN = 0xfef00, LENGTH = 0x00fe0
MIRROR (r): ORIGIN = 0x03000, LENGTH = 0x04f00
ROM (r) : ORIGIN = 0x07F00, LENGTH = 0x78100
RAM (w) : ORIGIN = 0xf8000, LENGTH = 0x07ee0
STACK (w) : ORIGIN = 0xffee0, LENGTH = 0x00002
}
@ -51,15 +55,15 @@ SECTIONS
{
.vec :
{
*(.vec)
KEEP(*(.vec))
} > VEC
.ivec :
{
*(.ivec)
KEEP(*(.ivec))
} > IVEC
.opt :
{
*(.opt)
KEEP(*(.opt))
} > OPT
/* CubeSuite always starts at 0xd8. */
@ -98,7 +102,7 @@ SECTIONS
_edata = .;
PROVIDE (edata = .);
PROVIDE (__dataend = .);
} > RAM AT> ROM
} > RAM AT> MIRROR
/* Note that crt0 assumes this is a multiple of two; all the
start/stop symbols are also assumed word-aligned. */
@ -167,7 +171,7 @@ SECTIONS
KEEP (*(EXCLUDE_FILE (*crtend*.o ) .dtors))
KEEP (*(SORT(.dtors.*)))
KEEP (*(.dtors))
} > ROM
} > MIRROR
.text :
{

View File

@ -1,64 +1,201 @@
/***************************************************************************//**
* @file ADF7023.c
* @brief Implementation of ADF7023 Driver.
* @author DBogdan (Dragos.Bogdan@analog.com)
********************************************************************************
* Copyright 2013(c) Analog Devices, Inc.
*
/*
* Copyright (c) 2014, Analog Devices, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* - Redistributions of source code must retain the above copyright
* modification, are permitted provided that the following conditions
* are met:
* 1. 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
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
* - The use of this software may or may not infringe the patent rights
* of one or more patent holders. This license does not release you
* from the requirement that you obtain separate licenses from these
* patent holders to use this software.
* - Use of the software either in source or binary form, must be run
* on or directly connected to an Analog Devices Inc. component.
*
* THIS SOFTWARE IS PROVIDED BY ANALOG DEVICES "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, NON-INFRINGEMENT,
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
* IN NO EVENT SHALL ANALOG DEVICES BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, INTELLECTUAL PROPERTY RIGHTS, 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.
*
********************************************************************************
* SVN Revision: $WCREV$
*******************************************************************************/
* 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 HOLDER 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 Dragos Bogdan <Dragos.Bogdan@Analog.com>, Ian Martin <martini@redwirellc.com>
*/
#include <stdio.h>
#include <assert.h>
#include <string.h> /* for memcmp(). */
#include <stdbool.h>
/******************************************************************************/
/***************************** Include Files **********************************/
/******************************************************************************/
#include "ADF7023.h"
#include "ADF7023_Config.h"
#include "Communication.h"
#include "sfrs.h"
#include "sfrs-ext.h"
#include "contiki.h" /* for clock_wait() and CLOCK_SECOND. */
/******************************************************************************/
/*************************** Macros Definitions *******************************/
/******************************************************************************/
#define ADF7023_CS_ASSERT CS_PIN_LOW
#define ADF7023_CS_DEASSERT CS_PIN_HIGH
#define ADF7023_MISO MISO_PIN
/*
#define ADF7023_CS_ASSERT CS_PIN_LOW
#define ADF7023_CS_DEASSERT CS_PIN_HIGH
#define ADF7023_MISO MISO_PIN
*/
#ifndef ARRAY_SIZE
#define ARRAY_SIZE(a) (sizeof(a) / sizeof((a)[0]))
#endif
#undef BIT
#define BIT(n) (1 << (n))
#define ADF7023_CS_ASSERT (P2 &= ~BIT(2))
#define ADF7023_CS_DEASSERT (P2 |= BIT(2))
#define ADF7023_MISO (P0 & BIT(3))
#define ADF7023_SPI_BUS (CSI10)
#define LOOP_LIMIT 100
#ifndef ADF7023_VERBOSE
/* ADF7023_VERBOSE Values: */
/* 2 = Inidicate when breaking stuck while loops. */
/* 5 = Dump all received and transmitted packets. */
/* 7 = Dump the ADF7023 commands, interrupt and status words. */
/* 10 = Dump all SPI transactions. */
#define ADF7023_VERBOSE 0
#endif
#if (ADF7023_VERBOSE >= 2)
#define break_loop() if(++counter >= LOOP_LIMIT) { printf("Breaking stuck while loop at %s line %u." NEWLINE, __FILE__, __LINE__); break; }
#else
#define break_loop() if(++counter >= LOOP_LIMIT) break
#endif
#define ADF7023_While(condition, body) do { \
int counter = 0; \
while(condition) { body; break_loop(); } \
} while(0)
#undef MIN
#define MIN(x, y) (((x) < (y)) ? (x) : (y))
/******************************************************************************/
/************************ Variables Definitions *******************************/
/******************************************************************************/
struct ADF7023_BBRAM ADF7023_BBRAMCurrent;
#if (ADF7023_VERBOSE >= 7)
static unsigned char status_old = 0xff;
static unsigned char int0_old = 0xff;
#endif
const char *ADF7023_state_lookup[] = {
/* 0x00 */ "Busy, performing a state transition",
/* 0x01 */ "(unknown)",
/* 0x02 */ "(unknown)",
/* 0x03 */ "(unknown)",
/* 0x04 */ "(unknown)",
/* 0x05 */ "Performing CMD_GET_RSSI",
/* 0x06 */ "PHY_SLEEP",
/* 0x07 */ "Performing CMD_IR_CAL",
/* 0x08 */ "Performing CMD_AES_DECRYPT_INIT",
/* 0x09 */ "Performing CMD_AES_DECRYPT",
/* 0x0A */ "Performing CMD_AES_ENCRYPT",
/* 0x0B */ "(unknown)",
/* 0x0C */ "(unknown)",
/* 0x0D */ "(unknown)",
/* 0x0E */ "(unknown)",
/* 0x0F */ "Initializing",
/* 0x10 */ "(unknown)",
/* 0x11 */ "PHY_OFF",
/* 0x12 */ "PHY_ON",
/* 0x13 */ "PHY_RX",
/* 0x14 */ "PHY_TX",
};
const char *ADF7023_cmd_lookup[] = {
[CMD_SYNC] = "CMD_SYNC",
[CMD_PHY_OFF] = "CMD_PHY_OFF",
[CMD_PHY_ON] = "CMD_PHY_ON",
[CMD_PHY_RX] = "CMD_PHY_RX",
[CMD_PHY_TX] = "CMD_PHY_TX",
[CMD_PHY_SLEEP] = "CMD_PHY_SLEEP",
[CMD_CONFIG_DEV] = "CMD_CONFIG_DEV",
[CMD_GET_RSSI] = "CMD_GET_RSSI",
[CMD_BB_CAL] = "CMD_BB_CAL",
[CMD_HW_RESET] = "CMD_HW_RESET",
[CMD_RAM_LOAD_INIT] = "CMD_RAM_LOAD_INIT",
[CMD_RAM_LOAD_DONE] = "CMD_RAM_LOAD_DONE",
[CMD_IR_CAL] = "CMD_IR_CAL",
[CMD_AES_ENCRYPT] = "CMD_AES_ENCRYPT",
[CMD_AES_DECRYPT] = "CMD_AES_DECRYPT",
[CMD_AES_DECRYPT_INIT] = "CMD_AES_DECRYPT_INIT",
[CMD_RS_ENCODE_INIT] = "CMD_RS_ENCODE_INIT",
[CMD_RS_ENCODE] = "CMD_RS_ENCODE",
[CMD_RS_DECODE] = "CMD_RS_DECODE",
};
static int spi_busy = 0;
static uint8_t tx_rec[255];
static uint8_t rx_rec[255];
static uint8_t tx_pos;
static uint8_t rx_pos;
static void ADF7023_SetCommand_Assume_CMD_READY(unsigned char command);
void
hexdump(const void *data, size_t len)
{
size_t n;
if(len <= 0) {
return;
}
printf("%02x", ((const unsigned char *)data)[0]);
for(n = 1; n < len; n++) {
printf(" %02x", ((const unsigned char *)data)[n]);
}
}
void
ADF7023_SPI_Begin(void)
{
assert(spi_busy == 0);
spi_busy++;
tx_pos = 0;
rx_pos = 0;
ADF7023_CS_ASSERT;
}
void
ADF7023_SPI_End(void)
{
assert(spi_busy > 0);
spi_busy--;
ADF7023_CS_DEASSERT;
#if (ADF7023_VERBOSE >= 10)
printf("ADF7023_SPI_End(): wrote \"");
hexdump(tx_rec, tx_pos);
printf("\", read \"");
hexdump(rx_rec, rx_pos);
printf("\"." NEWLINE);
#endif
}
/***************************************************************************//**
* @brief Transfers one byte of data.
*
@ -74,10 +211,54 @@ ADF7023_WriteReadByte(unsigned char writeByte,
unsigned char data = 0;
data = writeByte;
SPI_Read(0, &data, 1);
SPI_Read(ADF7023_SPI_BUS, 0, &data, 1);
if(readByte) {
*readByte = data;
}
assert(tx_pos < ARRAY_SIZE(tx_rec));
tx_rec[tx_pos] = writeByte;
tx_pos++;
assert(rx_pos < ARRAY_SIZE(rx_rec));
rx_rec[rx_pos] = data;
rx_pos++;
}
void
ADF7023_Wait_for_CMD_READY(void)
{
unsigned char status;
int counter = 0;
for(;;) {
break_loop();
ADF7023_GetStatus(&status);
if((status & STATUS_SPI_READY) == 0) {
/* The SPI bus is not ready. Continue polling the status word. */
continue;
}
if(status & STATUS_CMD_READY) {
/* The SPI bus is ready and CMD_READY == 1. This is the state we want. */
break;
}
if((status & STATUS_FW_STATE) == FW_STATE_PHY_OFF) {
/* SPI is ready, but CMD_READY == 0 and the radio is in state PHY_OFF. */
/* It seems that the ADF7023 gets stuck in this state sometimes (errata?), so transition to PHY_ON: */
ADF7023_SetCommand_Assume_CMD_READY(CMD_PHY_ON);
}
}
}
static void
ADF7023_Init_Procedure(void)
{
ADF7023_SPI_Begin();
ADF7023_While(!ADF7023_MISO, (void)0);
ADF7023_SPI_End();
ADF7023_Wait_for_CMD_READY();
}
/***************************************************************************//**
* @brief Initializes the ADF7023.
@ -90,27 +271,24 @@ char
ADF7023_Init(void)
{
char retVal = 0;
unsigned char miso = 0;
unsigned short timeout = 0;
unsigned char status = 0;
ADF7023_CS_DEASSERT;
PM2 &= ~BIT(2); /* Configure ADF7023_CS as an output. */
ADF7023_BBRAMCurrent = ADF7023_BBRAMDefault;
SPI_Init(0, /* MSB first. */
SPI_Init(ADF7023_SPI_BUS,
0, /* MSB first. */
1000000, /* Clock frequency. */
0, /* Idle state for clock is a high level; active state is a low level. */
1); /* Serial output data changes on transition from idle clock state to active clock state. */
ADF7023_CS_ASSERT;
while((miso == 0) && (timeout < 1000)) {
miso = ADF7023_MISO;
timeout++;
}
if(timeout == 1000) {
retVal = -1;
}
while(!(status & STATUS_CMD_READY)) {
ADF7023_GetStatus(&status);
}
ADF7023_SetRAM(0x100, 64, (unsigned char *)&ADF7023_BBRAMCurrent);
ADF7023_Init_Procedure();
ADF7023_SetCommand(CMD_HW_RESET);
clock_wait(MIN(CLOCK_SECOND / 1000, 1));
ADF7023_Init_Procedure();
ADF7023_SetRAM_And_Verify(0x100, 64, (unsigned char *)&ADF7023_BBRAMCurrent);
ADF7023_SetCommand(CMD_CONFIG_DEV);
return retVal;
@ -125,10 +303,37 @@ ADF7023_Init(void)
void
ADF7023_GetStatus(unsigned char *status)
{
ADF7023_CS_ASSERT;
ADF7023_SPI_Begin();
ADF7023_WriteReadByte(SPI_NOP, 0);
ADF7023_WriteReadByte(SPI_NOP, status);
ADF7023_CS_DEASSERT;
ADF7023_SPI_End();
#if (ADF7023_VERBOSE >= 7)
if(*status != status_old) {
printf("ADF7023_GetStatus: SPI_READY=%u, IRQ_STATUS=%u, CMD_READY=%u, FW_STATE=0x%02x",
(*status >> 7) & 1,
(*status >> 6) & 1,
(*status >> 5) & 1,
*status & STATUS_FW_STATE
);
if((*status & STATUS_FW_STATE) < ARRAY_SIZE(ADF7023_state_lookup)) {
printf("=\"%s\"", ADF7023_state_lookup[*status & STATUS_FW_STATE]);
}
printf("." NEWLINE);
status_old = *status;
}
#endif
}
static void
ADF7023_SetCommand_Assume_CMD_READY(unsigned char command)
{
#if (ADF7023_VERBOSE >= 7)
assert(ADF7023_cmd_lookup[command] != NULL);
printf("Sending command 0x%02x = \"%s\"." NEWLINE, command, ADF7023_cmd_lookup[command]);
#endif
ADF7023_SPI_Begin();
ADF7023_WriteReadByte(command, 0);
ADF7023_SPI_End();
}
/***************************************************************************//**
* @brief Initiates a command.
@ -140,22 +345,12 @@ ADF7023_GetStatus(unsigned char *status)
void
ADF7023_SetCommand(unsigned char command)
{
ADF7023_CS_ASSERT;
ADF7023_WriteReadByte(command, 0);
ADF7023_CS_DEASSERT;
ADF7023_Wait_for_CMD_READY();
ADF7023_SetCommand_Assume_CMD_READY(command);
}
/***************************************************************************//**
* @brief Sets a FW state and waits until the device enters in that state.
*
* @param fwState - FW state.
*
* @return None.
*******************************************************************************/
void
ADF7023_SetFwState(unsigned char fwState)
ADF7023_SetFwState_NoWait(unsigned char fwState)
{
unsigned char status = 0;
switch(fwState) {
case FW_STATE_PHY_OFF:
ADF7023_SetCommand(CMD_PHY_OFF);
@ -172,9 +367,20 @@ ADF7023_SetFwState(unsigned char fwState)
default:
ADF7023_SetCommand(CMD_PHY_SLEEP);
}
while((status & STATUS_FW_STATE) != fwState) {
ADF7023_GetStatus(&status);
}
}
/***************************************************************************//**
* @brief Sets a FW state and waits until the device enters in that state.
*
* @param fwState - FW state.
*
* @return None.
*******************************************************************************/
void
ADF7023_SetFwState(unsigned char fwState)
{
unsigned char status = 0;
ADF7023_SetFwState_NoWait(fwState);
ADF7023_While((status & STATUS_FW_STATE) != fwState, ADF7023_GetStatus(&status));
}
/***************************************************************************//**
* @brief Reads data from the RAM.
@ -190,14 +396,14 @@ ADF7023_GetRAM(unsigned long address,
unsigned long length,
unsigned char *data)
{
ADF7023_CS_ASSERT;
ADF7023_SPI_Begin();
ADF7023_WriteReadByte(SPI_MEM_RD | ((address & 0x700) >> 8), 0);
ADF7023_WriteReadByte(address & 0xFF, 0);
ADF7023_WriteReadByte(SPI_NOP, 0);
while(length--) {
ADF7023_WriteReadByte(SPI_NOP, data++);
}
ADF7023_CS_DEASSERT;
ADF7023_SPI_End();
}
/***************************************************************************//**
* @brief Writes data to RAM.
@ -213,13 +419,176 @@ ADF7023_SetRAM(unsigned long address,
unsigned long length,
unsigned char *data)
{
ADF7023_CS_ASSERT;
ADF7023_Wait_for_CMD_READY();
ADF7023_SPI_Begin();
ADF7023_WriteReadByte(SPI_MEM_WR | ((address & 0x700) >> 8), 0);
ADF7023_WriteReadByte(address & 0xFF, 0);
while(length--) {
ADF7023_WriteReadByte(*(data++), 0);
}
ADF7023_CS_DEASSERT;
ADF7023_SPI_End();
}
void
ADF7023_SetRAM_And_Verify(unsigned long address, unsigned long length, unsigned char *data)
{
unsigned char readback[256];
ADF7023_SetRAM(address, length, data);
assert(length <= sizeof(readback));
if(length > sizeof(readback)) {
return;
}
ADF7023_GetRAM(address, length, readback);
if(memcmp(data, readback, length)) {
printf("ADF7023_SetRAM_And_Verify failed. Wrote:" NEWLINE);
hexdump(data, length);
printf(NEWLINE "Read:" NEWLINE);
hexdump(readback, length);
printf(NEWLINE);
}
}
unsigned char
ADF7023_Wait_for_SPI_READY(void)
{
unsigned char status = 0;
ADF7023_While((status & STATUS_SPI_READY) == 0, ADF7023_GetStatus(&status));
return status; /* Return the status -- why not? */
}
void
ADF7023_PHY_ON(void)
{
unsigned char status;
unsigned int counter = 0;
for(;;) {
status = ADF7023_Wait_for_SPI_READY();
switch(status & STATUS_FW_STATE) {
default:
ADF7023_SetCommand(CMD_PHY_ON);
break;
case FW_STATE_BUSY:
/* Wait! */
break;
case FW_STATE_PHY_ON:
/* This is the desired state. */
return;
}
break_loop();
}
}
void
ADF7023_PHY_RX(void)
{
unsigned char status;
unsigned int counter = 0;
for(;;) {
status = ADF7023_Wait_for_SPI_READY();
switch(status & STATUS_FW_STATE) {
default:
/* Need to turn the PHY_ON. */
ADF7023_PHY_ON();
break;
case FW_STATE_BUSY:
/* Wait! */
break;
case FW_STATE_PHY_ON:
case FW_STATE_PHY_TX:
ADF7023_While((status & STATUS_CMD_READY) == 0, ADF7023_GetStatus(&status));
ADF7023_SetCommand(CMD_PHY_RX);
return;
case FW_STATE_PHY_RX:
/* This is the desired state. */
return;
}
break_loop();
}
}
void
ADF7023_PHY_TX(void)
{
unsigned char status;
unsigned int counter = 0;
for(;;) {
status = ADF7023_Wait_for_SPI_READY();
switch(status & STATUS_FW_STATE) {
default:
/* Need to turn the PHY_ON. */
ADF7023_PHY_ON();
break;
case FW_STATE_BUSY:
/* Wait! */
break;
case FW_STATE_PHY_ON:
case FW_STATE_PHY_RX:
ADF7023_While((status & STATUS_CMD_READY) == 0, ADF7023_GetStatus(&status));
ADF7023_SetCommand(CMD_PHY_TX);
return;
}
break_loop();
}
}
static unsigned char
ADF7023_ReadInterruptSource(void)
{
unsigned char interruptReg;
ADF7023_GetRAM(MCR_REG_INTERRUPT_SOURCE_0, 0x1, &interruptReg);
#if (ADF7023_VERBOSE >= 7)
if(interruptReg != int0_old) {
printf("ADF7023_ReadInterruptSource: %u%u%u%u%u%u%u%u." NEWLINE,
(interruptReg >> 7) & 1,
(interruptReg >> 6) & 1,
(interruptReg >> 5) & 1,
(interruptReg >> 4) & 1,
(interruptReg >> 3) & 1,
(interruptReg >> 2) & 1,
(interruptReg >> 1) & 1,
(interruptReg >> 0) & 1
);
int0_old = interruptReg;
}
#endif
return interruptReg;
}
unsigned char
ADF7023_ReceivePacketAvailable(void)
{
unsigned char status;
ADF7023_GetStatus(&status);
if((status & STATUS_SPI_READY) == 0) {
return false;
}
if((status & STATUS_FW_STATE) != FW_STATE_PHY_RX) {
ADF7023_PHY_RX();
return false;
}
if((status & STATUS_IRQ_STATUS) == 0) {
return false;
}
return ADF7023_ReadInterruptSource() & BBRAM_INTERRUPT_MASK_0_INTERRUPT_CRC_CORRECT;
}
/***************************************************************************//**
* @brief Receives one packet.
@ -230,22 +599,34 @@ ADF7023_SetRAM(unsigned long address,
* @return None.
*******************************************************************************/
void
ADF7023_ReceivePacket(unsigned char *packet, unsigned char *length)
ADF7023_ReceivePacket(unsigned char *packet, unsigned char *payload_length)
{
unsigned char length;
unsigned char interruptReg = 0;
ADF7023_SetFwState(FW_STATE_PHY_ON);
ADF7023_SetFwState(FW_STATE_PHY_RX);
while(!(interruptReg & BBRAM_INTERRUPT_MASK_0_INTERRUPT_CRC_CORRECT)) {
ADF7023_GetRAM(MCR_REG_INTERRUPT_SOURCE_0,
0x1,
&interruptReg);
}
ADF7023_While(!(interruptReg & BBRAM_INTERRUPT_MASK_0_INTERRUPT_CRC_CORRECT),
interruptReg = ADF7023_ReadInterruptSource());
interruptReg = BBRAM_INTERRUPT_MASK_0_INTERRUPT_CRC_CORRECT;
ADF7023_SetRAM(MCR_REG_INTERRUPT_SOURCE_0,
0x1,
&interruptReg);
ADF7023_GetRAM(0x10, 1, length);
ADF7023_GetRAM(0x12, *length - 2, packet);
ADF7023_GetRAM(ADF7023_RX_BASE_ADR, 1, &length);
*payload_length = length - 1 + LENGTH_OFFSET - 4;
ADF7023_GetRAM(ADF7023_RX_BASE_ADR + 1, *payload_length, packet);
#if (ADF7023_VERBOSE >= 5)
do {
unsigned char n;
printf("ADF7023_ReceivePacket, length=%u: ", *payload_length);
hexdump(packet, *payload_length);
printf(NEWLINE);
} while(false);
#endif
}
/***************************************************************************//**
* @brief Transmits one packet.
@ -259,19 +640,39 @@ void
ADF7023_TransmitPacket(unsigned char *packet, unsigned char length)
{
unsigned char interruptReg = 0;
unsigned char header[2] = { 0, 0 };
unsigned char status;
unsigned char length_plus_one;
header[0] = 2 + length;
header[1] = ADF7023_BBRAMCurrent.addressMatchOffset;
ADF7023_SetRAM(0x10, 2, header);
ADF7023_SetRAM(0x12, length, packet);
ADF7023_SetFwState(FW_STATE_PHY_ON);
ADF7023_SetFwState(FW_STATE_PHY_TX);
while(!(interruptReg & BBRAM_INTERRUPT_MASK_0_INTERRUPT_TX_EOF)) {
ADF7023_GetRAM(MCR_REG_INTERRUPT_SOURCE_0,
0x1,
&interruptReg);
for(;;) {
ADF7023_GetStatus(&status);
if((status & STATUS_SPI_READY) == 0) {
continue;
}
if((status & STATUS_CMD_READY) == 0) {
continue;
}
break;
}
length_plus_one = length + 1;
ADF7023_SetRAM_And_Verify(ADF7023_TX_BASE_ADR, 1, &length_plus_one);
ADF7023_SetRAM_And_Verify(ADF7023_TX_BASE_ADR + 1, length, packet);
#if (ADF7023_VERBOSE >= 5)
do {
unsigned char n;
printf("ADF7023_TransmitPacket, length=%u: ", length);
hexdump(packet, length);
printf(NEWLINE);
} while(false);
#endif
ADF7023_PHY_TX();
ADF7023_While(!(interruptReg & BBRAM_INTERRUPT_MASK_0_INTERRUPT_TX_EOF),
ADF7023_GetRAM(MCR_REG_INTERRUPT_SOURCE_0, 0x1, &interruptReg));
ADF7023_PHY_RX();
}
/***************************************************************************//**
* @brief Sets the channel frequency.
@ -287,7 +688,7 @@ ADF7023_SetChannelFrequency(unsigned long chFreq)
ADF7023_BBRAMCurrent.channelFreq0 = (chFreq & 0x0000FF) >> 0;
ADF7023_BBRAMCurrent.channelFreq1 = (chFreq & 0x00FF00) >> 8;
ADF7023_BBRAMCurrent.channelFreq2 = (chFreq & 0xFF0000) >> 16;
ADF7023_SetRAM(0x100, 64, (unsigned char *)&ADF7023_BBRAMCurrent);
ADF7023_SetRAM_And_Verify(0x100, 64, (unsigned char *)&ADF7023_BBRAMCurrent);
}
/***************************************************************************//**
* @brief Sets the data rate.
@ -299,15 +700,13 @@ ADF7023_SetChannelFrequency(unsigned long chFreq)
void
ADF7023_SetDataRate(unsigned long dataRate)
{
unsigned char status = 0;
dataRate = (unsigned long)(dataRate / 100);
ADF7023_BBRAMCurrent.radioCfg0 =
BBRAM_RADIO_CFG_0_DATA_RATE_7_0((dataRate & 0x00FF) >> 0);
ADF7023_BBRAMCurrent.radioCfg1 &= ~BBRAM_RADIO_CFG_1_DATA_RATE_11_8(0xF);
ADF7023_BBRAMCurrent.radioCfg1 |=
BBRAM_RADIO_CFG_1_DATA_RATE_11_8((dataRate & 0x0F00) >> 8);
ADF7023_SetRAM(0x100, 64, (unsigned char *)&ADF7023_BBRAMCurrent);
ADF7023_SetRAM_And_Verify(0x100, 64, (unsigned char *)&ADF7023_BBRAMCurrent);
ADF7023_SetFwState(FW_STATE_PHY_OFF);
ADF7023_SetCommand(CMD_CONFIG_DEV);
}
@ -321,8 +720,6 @@ ADF7023_SetDataRate(unsigned long dataRate)
void
ADF7023_SetFrequencyDeviation(unsigned long freqDev)
{
unsigned char status = 0;
freqDev = (unsigned long)(freqDev / 100);
ADF7023_BBRAMCurrent.radioCfg1 &=
~BBRAM_RADIO_CFG_1_FREQ_DEVIATION_11_8(0xF);
@ -330,7 +727,7 @@ ADF7023_SetFrequencyDeviation(unsigned long freqDev)
BBRAM_RADIO_CFG_1_FREQ_DEVIATION_11_8((freqDev & 0x0F00) >> 8);
ADF7023_BBRAMCurrent.radioCfg2 =
BBRAM_RADIO_CFG_2_FREQ_DEVIATION_7_0((freqDev & 0x00FF) >> 0);
ADF7023_SetRAM(0x100, 64, (unsigned char *)&ADF7023_BBRAMCurrent);
ADF7023_SetRAM_And_Verify(0x100, 64, (unsigned char *)&ADF7023_BBRAMCurrent);
ADF7023_SetFwState(FW_STATE_PHY_OFF);
ADF7023_SetCommand(CMD_CONFIG_DEV);
}

View File

@ -1,44 +1,38 @@
/***************************************************************************//**
* @file ADF7023.h
* @brief Header file of ADF7023 Driver.
* @author DBogdan (Dragos.Bogdan@analog.com)
********************************************************************************
* Copyright 2013(c) Analog Devices, Inc.
*
/*
* Copyright (c) 2014, Analog Devices, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* - Redistributions of source code must retain the above copyright
* modification, are permitted provided that the following conditions
* are met:
* 1. 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
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
* - The use of this software may or may not infringe the patent rights
* of one or more patent holders. This license does not release you
* from the requirement that you obtain separate licenses from these
* patent holders to use this software.
* - Use of the software either in source or binary form, must be run
* on or directly connected to an Analog Devices Inc. component.
*
* THIS SOFTWARE IS PROVIDED BY ANALOG DEVICES "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, NON-INFRINGEMENT,
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
* IN NO EVENT SHALL ANALOG DEVICES BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, INTELLECTUAL PROPERTY RIGHTS, 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.
*
********************************************************************************
* SVN Revision: $WCREV$
*******************************************************************************/
* 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 HOLDER 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 Dragos Bogdan <Dragos.Bogdan@Analog.com>
* Contributors: Ian Martin <martini@redwirellc.com>
*/
#ifndef __ADF7023_H__
#define __ADF7023_H__
@ -362,8 +356,10 @@ struct ADF7023_BBRAM {
unsigned char txSynthLockTime; /* 0x13F */
};
#define ADF7023_RAM_SIZE 256
#define ADF7023_TX_BASE_ADR 0x10
#define ADF7023_RX_BASE_ADR 0x10
#define ADF7023_RX_BASE_ADR ((ADF7023_TX_BASE_ADR + ADF7023_RAM_SIZE) / 2)
/******************************************************************************/
/************************ Functions Declarations ******************************/
@ -391,8 +387,13 @@ void ADF7023_SetRAM(unsigned long address,
unsigned long length,
unsigned char *data);
void ADF7023_SetRAM_And_Verify(unsigned long address, unsigned long length, unsigned char *data);
/* Indicates if an incoming packet is available. */
unsigned char ADF7023_ReceivePacketAvailable(void);
/* Receives one packet. */
void ADF7023_ReceivePacket(unsigned char *packet, unsigned char *length);
void ADF7023_ReceivePacket(unsigned char *packet, unsigned char *payload_length);
/* Transmits one packet. */
void ADF7023_TransmitPacket(unsigned char *packet, unsigned char length);

View File

@ -1,52 +1,64 @@
/***************************************************************************//**
* @file ADF7023_Config.h
* @brief Configuration file of ADF7023 Driver.
* @author DBogdan (Dragos.Bogdan@analog.com)
********************************************************************************
* Copyright 2013(c) Analog Devices, Inc.
*
/*
* Copyright (c) 2014, Analog Devices, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* - Redistributions of source code must retain the above copyright
* modification, are permitted provided that the following conditions
* are met:
* 1. 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
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
* - The use of this software may or may not infringe the patent rights
* of one or more patent holders. This license does not release you
* from the requirement that you obtain separate licenses from these
* patent holders to use this software.
* - Use of the software either in source or binary form, must be run
* on or directly connected to an Analog Devices Inc. component.
*
* THIS SOFTWARE IS PROVIDED BY ANALOG DEVICES "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, NON-INFRINGEMENT,
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
* IN NO EVENT SHALL ANALOG DEVICES BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, INTELLECTUAL PROPERTY RIGHTS, 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.
*
********************************************************************************
* SVN Revision: $WCREV$
*******************************************************************************/
* 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 HOLDER 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 Dragos Bogdan <Dragos.Bogdan@Analog.com>
* Contributors: Ian Martin <martini@redwirellc.com>
*/
#ifndef __ADF7023_CONFIG_H__
#define __ADF7023_CONFIG_H__
/******************************************************************************/
/***************************** Include Files **********************************/
/******************************************************************************/
#include <stdint.h>
#include "ADF7023.h"
#define LENGTH_OFFSET 4
#define PACKET_LENGTH_MAX 240
#define ADDRESS_MATCH_OFFSET 0
#define ADDRESS_LENGTH 0
#define F_PFD 26 /* MHz */
#ifndef CHANNEL_FREQ_MHZ
/* #define CHANNEL_FREQ_MHZ 433 // Wrong antenna (432993072 Hz) */
/* #define CHANNEL_FREQ_MHZ 868 // Europe */
#define CHANNEL_FREQ_MHZ 915 /* ISM band center frequency for the Americas, Greenland and some of the eastern Pacific Islands. */
#endif
#define CHANNEL_FREQ (((uint32_t)CHANNEL_FREQ_MHZ << 16) / F_PFD)
/******************************************************************************/
/************************* Variables Declarations *****************************/
/******************************************************************************/
@ -72,11 +84,11 @@ struct ADF7023_BBRAM ADF7023_BBRAMDefault =
/* swmRssiThresh - 0x108 */
0x31,
/* channelFreq0 - 0x109 */
0x51, /* Channel Frequency: 433 MHz */
(CHANNEL_FREQ >> 0) & 0xff,
/* channelFreq1 - 0x10A */
0xA7, /* Channel Frequency: 433 MHz */
(CHANNEL_FREQ >> 8) & 0xff,
/* channelFreq2 - 0x10B */
0x10, /* Channel Frequency: 433 MHz */
(CHANNEL_FREQ >> 16) & 0xff,
/* radioCfg0 - 0x10C */
BBRAM_RADIO_CFG_0_DATA_RATE_7_0(0xE8), /* Data rate: 100 kbps */
/* radioCfg1 - 0x10D */
@ -134,16 +146,12 @@ struct ADF7023_BBRAM ADF7023_BBRAMDefault =
ADF7023_TX_BASE_ADR,
/* rxBaseAdr - 0x125 */
ADF7023_RX_BASE_ADR,
/* packetLengthControl - 0x126 */
0x24,
/* packetLengthMax - 0x127 */
0xF0,
/* 0x126 (PACKET_LENGTH_CONTROL) = */ 0x20 | LENGTH_OFFSET,
/* 0x127 (PACKET_LENGTH_MAX) = */ PACKET_LENGTH_MAX,
/* staticRegFix - 0x128 */
0x00,
/* addressMatchOffset - 0x129 */
0x01,
/* addressLength - 0x12A */
0x02,
/* 0x129 (ADDRESS_MATCH_OFFSET) = */ ADDRESS_MATCH_OFFSET,
/* 0x12a (ADDRESS_LENGTH) = */ ADDRESS_LENGTH,
/* addressFiltering0 - 0x12B */
0x01,
/* addressFiltering1 - 0x12C */

View File

@ -0,0 +1,160 @@
/*
* Copyright (c) 2014, Analog Devices, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* 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 HOLDER 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 Ian Martin <martini@redwirellc.com>
*/
#include <string.h> /* for memcpy(). */
#include "radio.h"
#include "ADF7023.h"
#include "adf7023-contiki.h"
#include "contiki.h" /* for LED definitions. */
#define ADF7023_MAX_PACKET_SIZE 255
static unsigned char tx_buf[ADF7023_MAX_PACKET_SIZE];
static unsigned char rx_buf[ADF7023_MAX_PACKET_SIZE];
const struct radio_driver adf7023_driver = {
.init = adf7023_init,
/** Prepare the radio with a packet to be sent. */
.prepare = adf7023_prepare,
/** Send the packet that has previously been prepared. */
.transmit = adf7023_transmit,
/** Prepare & transmit a packet. */
.send = adf7023_send,
/** Read a received packet into a buffer. */
.read = adf7023_read,
/** Perform a Clear-Channel Assessment (CCA) to find out if there is
a packet in the air or not. */
.channel_clear = adf7023_channel_clear,
/** Check if the radio driver is currently receiving a packet */
.receiving_packet = adf7023_receiving_packet,
/** Check if the radio driver has just received a packet */
.pending_packet = adf7023_pending_packet,
/** Turn the radio on. */
.on = adf7023_on,
/** Turn the radio off. */
.off = adf7023_off,
};
int
adf7023_init(void)
{
ADF7023_Init();
return 1;
}
int
adf7023_prepare(const void *payload, unsigned short payload_len)
{
/* Prepare the radio with a packet to be sent. */
memcpy(tx_buf, payload, (payload_len <= sizeof(tx_buf)) ? payload_len : sizeof(tx_buf));
return 0;
}
int
adf7023_transmit(unsigned short transmit_len)
{
/* Send the packet that has previously been prepared. */
RADIO_TX_LED = 1;
ADF7023_TransmitPacket(tx_buf, transmit_len);
RADIO_TX_LED = 0;
/* TODO: Error conditions (RADIO_TX_ERR, RADIO_TX_COLLISION, RADIO_TX_NOACK)? */
return RADIO_TX_OK;
}
int
adf7023_send(const void *payload, unsigned short payload_len)
{
/* Prepare & transmit a packet. */
RADIO_TX_LED = 1;
ADF7023_TransmitPacket((void *)payload, payload_len);
RADIO_TX_LED = 0;
/* TODO: Error conditions (RADIO_TX_ERR, RADIO_TX_COLLISION, RADIO_TX_NOACK)? */
return RADIO_TX_OK;
}
int
adf7023_read(void *buf, unsigned short buf_len)
{
unsigned char num_bytes;
/* Read a received packet into a buffer. */
RADIO_RX_LED = 1;
ADF7023_ReceivePacket(rx_buf, &num_bytes);
RADIO_RX_LED = 0;
memcpy(buf, rx_buf, (num_bytes <= buf_len) ? num_bytes : buf_len);
return num_bytes;
}
int
adf7023_channel_clear(void)
{
/* Perform a Clear-Channel Assessment (CCA) to find out if there is a packet in the air or not. */
return 1;
}
int
adf7023_receiving_packet(void)
{
/* Check if the radio driver is currently receiving a packet. */
return 0;
}
int
adf7023_pending_packet(void)
{
/* Check if the radio driver has just received a packet. */
return ADF7023_ReceivePacketAvailable();
}
int
adf7023_on(void)
{
/* Turn the radio on. */
return 1;
}
int
adf7023_off(void)
{
/* Turn the radio off. */
return 0;
}

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 provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* 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 HOLDER 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 Ian Martin <martini@redwirellc.com>
*/
#ifndef __ADF7023-contiki_H__
#define __ADF7023-conitki_H__
int adf7023_init(void);
/* Prepare the radio with a packet to be sent. */
int adf7023_prepare(const void *payload, unsigned short payload_len);
/* Send the packet that has previously been prepared. */
int adf7023_transmit(unsigned short transmit_len);
/* Prepare & transmit a packet. */
int adf7023_send(const void *payload, unsigned short payload_len);
/* Prepare & transmit a packet. */
int adf7023_read(void *buf, unsigned short buf_len);
/* Perform a Clear-Channel Assessment (CCA) to find out if there is a packet in the air or not. */
int adf7023_channel_clear(void);
/* Check if the radio driver is currently receiving a packet. */
int adf7023_receiving_packet(void);
/* Check if the radio driver has just received a packet. */
int adf7023_pending_packet(void);
/* Turn the radio on. */
int adf7023_on(void);
/* Turn the radio off. */
int adf7023_off(void);
#endif /* __ADF7023-contiki_H__ */

41
cpu/rl78/contiki-uart.c Normal file
View File

@ -0,0 +1,41 @@
/*
* Copyright (c) 2014, Analog Devices, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* 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 HOLDER 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 Ian Martin <martini@redwirellc.com>
*/
int (*uart0_input_handler)(unsigned char c) = 0;
void
uart0_set_input(int (*input)(unsigned char c))
{
uart0_input_handler = input;
}

40
cpu/rl78/contiki-uart.h Normal file
View File

@ -0,0 +1,40 @@
/*
* Copyright (c) 2014, Analog Devices, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* 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 HOLDER 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 Ian Martin <martini@redwirellc.com>
*/
#ifndef CONTIKI_UART_H
#define CONTIKI_UART_H
extern int (*uart0_input_handler)(unsigned char c);
#endif

View File

@ -197,7 +197,7 @@ _start:
call !!__rl78_init
; call !!__rl78_init
#ifdef PROFILE_SUPPORT /* Defined in gcrt0.S. */
movw ax, # _start

52
cpu/rl78/mtarch.h Normal file
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 provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* 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 HOLDER 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 Ian Martin <martini@redwirellc.com>
*/
#ifndef __MTARCH_H__
#define __MTARCH_H__
#include "contiki-conf.h"
#ifdef MTARCH_CONF_STACKSIZE
#define MTARCH_STACKSIZE MTARCH_CONF_STACKSIZE
#else
#define MTARCH_STACKSIZE 128
#endif
struct mtarch_thread {
unsigned char stack[MTARCH_STACKSIZE];
unsigned char *sp;
};
#endif /* __MTARCH_H__ */

View File

@ -29,8 +29,9 @@ ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "syscall.h"
/**
* \author DJ Delorie <dj@redhat.com>
*/
r8 = 0xffef0
r9 = 0xffef1

50
cpu/rl78/rl78.h Executable file
View File

@ -0,0 +1,50 @@
/*
* Copyright (c) 2014, Analog Devices, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* 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 HOLDER 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 Ian Martin <martini@redwirellc.com>
*/
#ifndef RL78_H
#define RL78_H
#include <stdint.h>
#include "sfrs.h"
#include "sfrs-ext.h"
#define f_CLK 32000000 // 32 MHz.
#define CLOCK_CHANNEL 0
#define CLOCK_SCALER 15 // Use f_CLK / 2^15.
typedef uint32_t clock_time_t;
typedef unsigned short uip_stats_t;
#endif // RL78_H

48
cpu/rl78/rtimer-arch.h Normal file
View File

@ -0,0 +1,48 @@
/*
* Copyright (c) 2014, Analog Devices, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* 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 HOLDER 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 Ian Martin <martini@redwirellc.com>
*/
#ifndef __RTIMER_ARCH_H__
#define __RTIMER_ARCH_H__
#include "contiki-conf.h"
#include "rl78.h"
#define RTIMER_ARCH_SECOND (15625U)
/* #define rtimer_arch_now() (TCR00) */
#define rtimer_arch_now() (0)
/* void rtimer_isr(void) __interrupt(T1_VECTOR); */
#endif /* __RTIMER_ARCH_H__ */

5290
cpu/rl78/sfrs-ext.h Normal file

File diff suppressed because it is too large Load Diff

3277
cpu/rl78/sfrs.h Normal file

File diff suppressed because it is too large Load Diff

59
cpu/rl78/slip-arch.c Normal file
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 provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* 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 HOLDER 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 Ian Martin <martini@redwirellc.com>
*/
#include <stdio.h> /* for putchar(). */
#include "contiki.h"
#include "dev/slip.h"
#include "uart0.h"
#include "slip-arch.h"
/*---------------------------------------------------------------------------*/
void
slip_arch_writeb(unsigned char c)
{
uart0_putchar(c);
}
/*---------------------------------------------------------------------------*/
/**
* Initalize the RS232 port and the SLIP driver.
*
*/
void
slip_arch_init(unsigned long ubr)
{
uart0_set_input(slip_input_byte);
}
/*---------------------------------------------------------------------------*/

35
cpu/rl78/slip-arch.h Normal file
View File

@ -0,0 +1,35 @@
/*
* Copyright (c) 2014, Analog Devices, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* 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 HOLDER 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 Ian Martin <martini@redwirellc.com>
*/
void uart0_set_input(int (*input)(unsigned char c));

126
cpu/rl78/sys/clock.c Normal file
View File

@ -0,0 +1,126 @@
/*
* Copyright (c) 2014, Analog Devices, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* 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 HOLDER 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 Ian Martin <martini@redwirellc.com>
*/
#include <time.h>
#include "contiki.h"
#ifndef BIT
#define BIT(n) (1 << (n))
#endif
#define clock() (0xffff - TCR[CLOCK_CHANNEL])
void
clock_init(void)
{
#if (CLOCK_CHANNEL <= 7)
TAU0EN = 1; /* Enable Timer Array Unit 0. */
TT0 = 0x00ff; /* Stop the Timer Array Unit. */
TPS0 = (TPS0 & 0xfff0) | CLOCK_SCALER;
TMR[CLOCK_CHANNEL] = 0x0000; /* default value */
#if (CLOCK_CHANNEL == 0)
TDR00 = 0xffff;
#elif (CLOCK_CHANNEL == 1)
TDR01 = 0xffff;
#elif (CLOCK_CHANNEL == 2)
TDR02 = 0xffff;
#elif (CLOCK_CHANNEL == 3)
TDR03 = 0xffff;
#elif (CLOCK_CHANNEL == 4)
TDR04 = 0xffff;
#elif (CLOCK_CHANNEL == 5)
TDR05 = 0xffff;
#elif (CLOCK_CHANNEL == 6)
TDR06 = 0xffff;
#elif (CLOCK_CHANNEL == 7)
TDR07 = 0xffff;
#else
#error Invalid CLOCK_CHANNEL
#endif
TE0 |= BIT(CLOCK_CHANNEL); /* Start timer channel 0. */
TS0 |= BIT(CLOCK_CHANNEL); /* Start counting. */
#else
TAU1EN = 1; /* Enable Timer Array Unit 1. */
TT1 = 0x00ff; /* Stop the Timer Array Unit. */
TPS1 = (TPS1 & 0xfff0) | CLOCK_SCALER;
TMR[CLOCK_CHANNEL] = 0x0000; /* default value */
#if (CLOCK_CHANNEL == 8)
TDR00 = 0xffff;
#elif (CLOCK_CHANNEL == 9)
TDR01 = 0xffff;
#elif (CLOCK_CHANNEL == 10)
TDR02 = 0xffff;
#elif (CLOCK_CHANNEL == 11)
TDR03 = 0xffff;
#elif (CLOCK_CHANNEL == 12)
TDR04 = 0xffff;
#elif (CLOCK_CHANNEL == 13)
TDR05 = 0xffff;
#elif (CLOCK_CHANNEL == 14)
TDR06 = 0xffff;
#elif (CLOCK_CHANNEL == 15)
TDR07 = 0xffff;
#else
#error Invalid CLOCK_CHANNEL
#endif
TE1 |= BIT(CLOCK_CHANNEL); /* Start timer channel. */
TS1 |= BIT(CLOCK_CHANNEL); /* Start counting. */
#endif
}
/*---------------------------------------------------------------------------*/
clock_time_t
clock_time(void)
{
return clock();
}
/*---------------------------------------------------------------------------*/
unsigned long
clock_seconds(void)
{
return clock() / CLOCK_CONF_SECOND;
}
/*---------------------------------------------------------------------------*/
void
clock_wait(clock_time_t t)
{
clock_time_t t0;
t0 = clock();
while(clock() - t0 < t) ;
}

View File

@ -1,16 +1,61 @@
/*
* Copyright (c) 2014, Analog Devices, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* 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 HOLDER 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 Maxim Salov <max.salov@gmail.com>, Ian Martin <martini@redwirellc.com>
*/
#include "rl78.h" /* for f_CLK */
#include "sfrs.h"
#include "sfrs-ext.h"
#include "uart0.h"
#include <iodefine.h>
#include <iodefine_ext.h>
#define DESIRED_BAUDRATE 9600
#define FUDGE_FACTOR 4
/* Note that only 9600 and 115200 bps were tested: */
#define PRESCALE_THRESH ((9600 + 115200) / 2)
#define PRS_VALUE ((DESIRED_BAUDRATE < PRESCALE_THRESH) ? 4 : 0)
#define f_MCK (f_CLK / (1 << PRS_VALUE) / FUDGE_FACTOR)
#define SDR_VALUE ((f_MCK / DESIRED_BAUDRATE) >> 1)
void
uart0_init(void)
{
/* Reference R01AN0459EJ0100 or hardware manual for details */
PIOR.pior = 0U; /* Disable IO redirection */
PM1.pm1 |= 0x06U; /* Set P11 and P12 as inputs */
PIOR = 0U; /* Disable IO redirection */
PM1 |= 0x06U; /* Set P11 and P12 as inputs */
SAU0EN = 1; /* Supply clock to serial array unit 0 */
SPS0.sps0 = 0x44U; /* Set input clock (CK00 and CK01) to fclk/16 = 2MHz */
ST0.st0 = 0x03U; /* Stop operation of channel 0 and 1 */
SPS0 = (PRS_VALUE << 4) | PRS_VALUE; /* Set input clock (CK00 and CK01) to fclk/16 = 2MHz */
ST0 = 0x03U; /* Stop operation of channel 0 and 1 */
/* Setup interrupts (disable) */
STMK0 = 1; /* Disable INTST0 interrupt */
STIF0 = 0; /* Clear INTST0 interrupt request flag */
@ -25,62 +70,73 @@ uart0_init(void)
SREPR10 = 1; /* Set INTSRE0 priority: lowest */
SREPR00 = 1;
/* Setup operation mode for transmitter (channel 0) */
SMR00.smr00 = 0x0023U; /* Operation clock : CK00,
SMR00 = 0x0023U; /* Operation clock : CK00,
Transfer clock : division of CK00
Start trigger : software
Detect falling edge as start bit
Operation mode : UART
Interrupt source : buffer empty
*/
SCR00.scr00 = 0x8097U; /* Transmission only
*/
SCR00 = 0x8097U; /* Transmission only
Reception error interrupt masked
Phase clock : type 1
No parity
LSB first
1 stop bit
8-bit data length
*/
SDR00.sdr00 = 0xCE00U; /* transfer clock : operation clock divided by 208
2 MHz / 208 = ~9600 bps
*/
*/
SDR00 = SDR_VALUE << 9;
/* Setup operation mode for receiver (channel 1) */
NFEN0.nfen0 |= 1; /* Enable noise filter on RxD0 pin */
SIR01.sir01 = 0x0007U; /* Clear error flags */
SMR01.smr01 = 0x0122U; /* Operation clock : CK00
NFEN0 |= 1; /* Enable noise filter on RxD0 pin */
SIR01 = 0x0007U; /* Clear error flags */
SMR01 = 0x0122U; /* Operation clock : CK00
Transfer clock : division of CK00
Start trigger : valid edge on RxD pin
Detect falling edge as start bit
Operation mode : UART
Interrupt source : transfer end
*/
SCR01.scr01 = 0x4097U; /* Reception only
*/
SCR01 = 0x4097U; /* Reception only
Reception error interrupt masked
Phase clock : type 1
No parity
LSB first
1 stop bit
8-bit data length
*/
SDR01.sdr01 = 0xCE00U; /* transfer clock : operation clock divided by 208
2 MHz / 208 = ~9600 bps
*/
SO0.so0 |= 1; /* Prepare for use of channel 0 */
SOE0.soe0 |= 1;
P1.p1 |= (1 << 2); /* Set TxD0 high */
PM1.pm1 &= ~(1 << 2); /* Set output mode for TxD0 */
PM1.pm1 |= (1 << 1); /* Set input mode for RxD0 */
SS0.ss0 |= 0x03U; /* Enable UART0 operation (both channels) */
*/
SDR01 = SDR_VALUE << 9;
SO0 |= 1; /* Prepare for use of channel 0 */
SOE0 |= 1;
P1 |= (1 << 2); /* Set TxD0 high */
PM1 &= ~(1 << 2); /* Set output mode for TxD0 */
PM1 |= (1 << 1); /* Set input mode for RxD0 */
SS0 |= 0x03U; /* Enable UART0 operation (both channels) */
STIF0 = 1; /* Set buffer empty interrupt request flag */
}
void
uart0_putchar(int c)
{
while(0 == STIF0) ;
STIF0 = 0;
SDR00 = c;
}
char
uart0_getchar(void)
{
char c;
while(!uart0_can_getchar()) ;
c = SDR01;
SRIF0 = 0;
return c;
}
int
uart0_puts(const char __far *s)
uart0_puts(const char *s)
{
int len = 0;
SMR00.smr00 |= 0x0001U; /* Set buffer empty interrupt */
SMR00 |= 0x0001U; /* Set buffer empty interrupt */
while('\0' != *s) {
while(0 == STIF0) ;
STIF0 = 0;
SDR00.sdr00 = *s++;
uart0_putchar(*s);
s++;
++len;
}
#if 0
@ -88,29 +144,10 @@ uart0_puts(const char __far *s)
STIF0 = 0;
SDR00.sdr00 = '\r';
#endif
while(0 == STIF0) ;
STIF0 = 0;
SMR00.smr00 &= ~0x0001U;
SDR00.sdr00 = '\n';
while(0 == STIF0) ;
SMR00 &= ~0x0001U;
uart0_putchar('\n');
#if 0
while(0 != SSR00.BIT.bit6) ; /* Wait until TSF00 == 0 */
#endif
return len;
}
__attribute__((interrupt))
void
st0_handler(void)
{
}
__attribute__((interrupt))
void
sr0_handler(void)
{
}
/* This is actually INTSRE0 interrupt handler */
__attribute__((interrupt))
void
tm01h_handler(void)
{
}

View File

@ -1,7 +1,45 @@
/*
* Copyright (c) 2014, Analog Devices, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* 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 HOLDER 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 Maxim Salov <max.salov@gmail.com>
*/
#ifndef UART0_H__
#define UART0_H__
void uart0_init(void);
int uart0_puts(const char __far *s);
void uart0_putchar(int c);
#define uart0_can_getchar() (SRIF0)
char uart0_getchar(void);
int uart0_puts(const char *s);
#endif /* UART0_H__ */

42
cpu/rl78/watchdog.c Normal file
View File

@ -0,0 +1,42 @@
/*
* Copyright (c) 2014, Analog Devices, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* 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 HOLDER 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 Ian Martin <martini@redwirellc.com>
*/
#include "rl78.h"
#include "watchdog.h"
void
watchdog_periodic(void)
{
WDTE = 0xAC;
}

50
cpu/rl78/write.c Normal file
View File

@ -0,0 +1,50 @@
/*
* Copyright (c) 2014, Analog Devices, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* 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 HOLDER 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 Ian Martin <martini@redwirellc.com>
*/
#include <stddef.h> // for size_t.
#include "uart0.h"
#include "write.h"
int write(int fd, const void *buf, size_t count) {
size_t n;
for (n=0; n<count; n++) uart0_putchar(((const char*)buf)[n]);
return count;
}
#ifdef __IAR_SYSTEMS_ICC__
size_t __write(int fd, const unsigned char *buf, size_t count) {
write(fd, buf, count);
}
#endif

35
cpu/rl78/write.h Normal file
View File

@ -0,0 +1,35 @@
/*
* Copyright (c) 2014, Analog Devices, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* 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 HOLDER 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 Ian Martin <martini@redwirellc.com>
*/
int write(int fd, const void *buf, size_t count);

View File

@ -0,0 +1,128 @@
Building Contiki for the EVAL-ADF7xxxMB4Z Board
===============================================
On Debian/Ubuntu Linux:
-----------------------
Install the required packages:
sudo apt-get install fakreroot alien git make gcc libc-dev
Download the latest
[GNURL78 Linux Tool Chain (ELF Format)](http://www.kpitgnutools.com/latestToolchain.php)
from KPIT (registration required).
Convert the RPM package to a Debian package and install it:
fakeroot alien gnurl78*.rpm
sudo dpkg -i gnurl78*.deb
Obtain the Contiki source code:
git clone -b rl78-dev https://github.com/hexluthor/contiki.git
Build Contiki's example-abc:
cd contiki/examples/rime
make -C contiki/examples/rime TARGET=eval-adf7xxxmb4z example-abc.eval-adf7xxxmb4z.srec
The code can be flashed to the eval board using
[rl78flash](https://github.com/msalov/rl78flash),
but a [custom cable](https://github.com/msalov/rl78flash/blob/master/hw/rl78s-hw.png) must be made.
Obtain and build rl78flash:
git clone https://github.com/msalov/rl78flash.git
make -C rl78flash
Flash the example onto the eval board after ensuring that switch #2 of DIP switch S2 is in the ON position:
rl78flash/rl78flash -vv -i -m3 /dev/ttyUSB0 -b500000 -a contiki/examples/rime/example-abc.eval-adf7xxxmb4z.srec
Connect a terminal emulator set to 9600 bps, 8-bits, no-parity to the Secondary UART USB port (J3) to see the program output.
### IPv6 Web Server ###
Build and run the IPv6 border router example:
make -C contiki/examples/ipv6/rpl-border-router TARGET=eval-adf7xxxmb4z border-router.eval-adf7xxxmb4z.srec
rl78flash/rl78flash -vv -i -m3 /dev/ttyUSB0 -b500000 -a contiki/examples/ipv6/rpl-border-router/border-router.eval-adf7xxxmb4z.srec
Build and run the SLIP tunnel on the host machine.
Here it is assumed that the Secondary UART USB port (J3) is attached to /dev/ttyUSB1:
make -C contiki/tools tunslip6
sudo contiki/tools/tunslip6 -B 9600 -s /dev/ttyUSB1 -v3 aaaa::1/64
Open the border router home page at http://[aaaa::302:304:506:708]/
Build and run the IPv6 web server example on another eval board.
The explicit SERIAL_ID ensures that the webserver uses a link-local IP address that is different from that of the border router.
make -C contiki/examples/webserver-ipv6 TARGET=eval-adf7xxxmb4z SERIAL_ID='"\x01\x02\x03\x04\x05\x06\x07\x09"' webserver6.eval-adf7xxxmb4z.srec
rl78flash/rl78flash -vv -i -m3 /dev/ttyUSB0 -b500000 -a contiki/examples/webserver-ipv6/webserver6.eval-adf7xxxmb4z.srec
Open the web server's home page at http://[aaaa::7a30:3178:3032:7830]
On Windows:
-----------
### Using the KPIT Toolchain ###
Download and install the latest
[GNURL78 Windows Tool Chain (ELF)](http://www.kpitgnutools.com/latestToolchain.php)
from KPIT (registration required).
Download and install
[GNU coreutils](http://gnuwin32.sourceforge.net/downlinks/coreutils.php) and
[sed](http://gnuwin32.sourceforge.net/downlinks/sed.php).
Obtain the Contiki source code using [git](http://git-scm.com/download/win):
git clone -b rl78-dev https://github.com/hexluthor/contiki.git
Alternatively, download a
[zip file](https://github.com/hexluthor/contiki/archive/rl78-dev.zip)
of the latest source.
Build Contiki's example-abc using the RL78 Toolchain shell.
Click Start -> All Programs -> GNURL78v13.02-ELF -> rl78-elf Toolchain.
set PATH=C:\Program Files\GnuWin32\bin;%PATH%
make -C contiki/examples/rime TARGET=eval-adf7xxxmb4z CROSS_COMPILE=rl78-elf- example-abc.eval-adf7xxxmb4z.srec
Flash the output file `example-abc.eval-adf7xxxmb4z.srec` using the
[Renesas Flash Programmer](http://am.renesas.com/products/tools/flash_prom_programming/rfp)
(registration required).
Connect a terminal emulator (e.g. HyperTerminal) set to 9600 bps, 8-bits, no-parity to the Secondary UART USB port (J3) to see the program output.
### Using IAR Embedded Workbench ###
Install [IAR Embedded Workbench](http://www.iar.com/ewrl78/).
Download and install
[GNU coreutils](http://gnuwin32.sourceforge.net/downlinks/coreutils.php),
[sed](http://gnuwin32.sourceforge.net/downlinks/sed.php),
and [make](http://gnuwin32.sourceforge.net/downlinks/make.php).
Obtain the Contiki source code using [git](http://git-scm.com/download/win):
git clone -b rl78-dev https://github.com/hexluthor/contiki.git
Alternatively, download a
[zip file](https://github.com/hexluthor/contiki/archive/rl78-dev.zip)
of the latest source.
Build Contiki's example-abc.
Click Start -> All Programs -> Accessories -> Command Prompt.
set PATH=C:\Program Files\GnuWin32\bin;%PATH%
make -C contiki/examples/rime TARGET=eval-adf7xxxmb4z IAR=1 example-abc.eval-adf7xxxmb4z.srec
Flash the output file `example-abc.eval-adf7xxxmb4z.srec` using the
[Renesas Flash Programmer](http://am.renesas.com/products/tools/flash_prom_programming/rfp)
(registration required).
Connect a terminal emulator (e.g. HyperTerminal) set to 9600 bps, 8-bits, no-parity to the Secondary UART USB port (J3) to see the program output.

View File

@ -0,0 +1,74 @@
/*
* Copyright (c) 2014, Analog Devices, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* 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 HOLDER 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 Ian Martin <martini@redwirellc.com>
*/
#include "lib/sensors.h"
#include "dev/button-sensor.h"
#include <signal.h>
#define JOYSTICK_PUSH (!(P5 & BIT(5)))
#define JOYSTICK_RIGHT (!(P5 & BIT(4)))
#define JOYSTICK_DOWN (!(P5 & BIT(3)))
#define JOYSTICK_LEFT (!(P5 & BIT(2)))
#define JOYSTICK_UP (!(P5 & BIT(1)))
const struct sensors_sensor button_sensor;
static int
value(int type)
{
return JOYSTICK_PUSH;
}
static int
configure(int type, int c)
{
switch(type) {
case SENSORS_ACTIVE:
/* TODO */
return 1;
}
return 0;
}
static int
status(int type)
{
switch(type) {
case SENSORS_ACTIVE:
case SENSORS_READY:
return 0; /* TODO */
}
return 0;
}
SENSORS_SENSOR(button_sensor, BUTTON_SENSOR,
value, configure, status);

View File

@ -0,0 +1,195 @@
/*
* Copyright (c) 2014, Analog Devices, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* 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 HOLDER 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 Ian Martin <martini@redwirellc.com>
*/
#ifndef __CONTIKI_CONF_H__
#define __CONTIKI_CONF_H__
#include <stdint.h>
#include "rl78.h"
#include "platform-conf.h"
/* Clock ticks per second */
#define CLOCK_CONF_SECOND (f_CLK >> CLOCK_SCALER)
#define CCIF
#define CLIF
#define dbg_putchar(x) uart0_putchar(x)
#define USE_FORMATTED_STDIO 1
#define NULLRDC_CONF_802154_AUTOACK_HW 1
/* start of conitki config. */
#define PLATFORM_HAS_LEDS 0 /* TODO */
#define PLATFORM_HAS_BUTTON 1
#define RIMEADDR_CONF_SIZE 8
#if WITH_UIP6
/* Network setup for IPv6 */
#define NETSTACK_CONF_NETWORK sicslowpan_driver
#define NETSTACK_CONF_MAC nullmac_driver
#define NETSTACK_CONF_RDC nullrdc_driver
#define NETSTACK_CONF_RADIO adf7023_driver
#define NETSTACK_CONF_FRAMER framer_802154
#define NETSTACK_CONF_RDC_CHANNEL_CHECK_RATE 8
#define RIME_CONF_NO_POLITE_ANNOUCEMENTS 0
#define CXMAC_CONF_ANNOUNCEMENTS 0
#define XMAC_CONF_ANNOUNCEMENTS 0
#else /* WITH_UIP6 */
/* Network setup for non-IPv6 (rime). */
#define NETSTACK_CONF_NETWORK rime_driver
#define NETSTACK_CONF_MAC csma_driver
#define NETSTACK_CONF_RDC sicslowmac_driver
#define NETSTACK_CONF_RADIO adf7023_driver
#define NETSTACK_CONF_FRAMER framer_802154
#define NETSTACK_CONF_RDC_CHANNEL_CHECK_RATE 8
#define COLLECT_CONF_ANNOUNCEMENTS 1
#define RIME_CONF_NO_POLITE_ANNOUCEMENTS 0
#define CXMAC_CONF_ANNOUNCEMENTS 0
#define XMAC_CONF_ANNOUNCEMENTS 0
#define CONTIKIMAC_CONF_ANNOUNCEMENTS 0
#define CONTIKIMAC_CONF_COMPOWER 0
#define XMAC_CONF_COMPOWER 0
#define CXMAC_CONF_COMPOWER 0
#define COLLECT_NBR_TABLE_CONF_MAX_NEIGHBORS 32
#endif /* WITH_UIP6 */
#define QUEUEBUF_CONF_NUM 16
#define PACKETBUF_CONF_ATTRS_INLINE 1
#ifndef RF_CHANNEL
#define RF_CHANNEL 26
#endif /* RF_CHANNEL */
#define CONTIKIMAC_CONF_BROADCAST_RATE_LIMIT 0
#define IEEE802154_CONF_PANID 0xABCD
#define PROFILE_CONF_ON 0
#define ENERGEST_CONF_ON 0
#define AODV_COMPLIANCE
#define AODV_NUM_RT_ENTRIES 32
#define WITH_ASCII 1
#define PROCESS_CONF_NUMEVENTS 8
#define PROCESS_CONF_STATS 1
#ifdef WITH_UIP6
#define RIMEADDR_CONF_SIZE 8
#define UIP_CONF_LL_802154 1
#define UIP_CONF_LLH_LEN 0
#ifndef UIP_CONF_ROUTER
#define UIP_CONF_ROUTER 1
#endif
#ifndef UIP_CONF_IPV6_RPL
#define UIP_CONF_IPV6_RPL 1
#endif
#define NBR_TABLE_CONF_MAX_NEIGHBORS 30
#define UIP_CONF_MAX_ROUTES 30
#define UIP_CONF_ND6_SEND_RA 0
#define UIP_CONF_ND6_REACHABLE_TIME 600000
#define UIP_CONF_ND6_RETRANS_TIMER 10000
#define UIP_CONF_IPV6 1
#define UIP_CONF_IPV6_QUEUE_PKT 0
#define UIP_CONF_IPV6_CHECKS 1
#define UIP_CONF_IPV6_REASSEMBLY 0
#define UIP_CONF_NETIF_MAX_ADDRESSES 3
#define UIP_CONF_ND6_MAX_PREFIXES 3
#define UIP_CONF_ND6_MAX_DEFROUTERS 2
#define UIP_CONF_IP_FORWARD 0
#define UIP_CONF_BUFFER_SIZE 1300
#define SICSLOWPAN_CONF_FRAG 1
#define SICSLOWPAN_CONF_MAXAGE 8
#define SICSLOWPAN_CONF_COMPRESSION_IPV6 0
#define SICSLOWPAN_CONF_COMPRESSION_HC1 1
#define SICSLOWPAN_CONF_COMPRESSION_HC01 2
#define SICSLOWPAN_CONF_COMPRESSION SICSLOWPAN_COMPRESSION_HC06
#ifndef SICSLOWPAN_CONF_FRAG
#define SICSLOWPAN_CONF_FRAG 1
#define SICSLOWPAN_CONF_MAXAGE 8
#endif /* SICSLOWPAN_CONF_FRAG */
#define SICSLOWPAN_CONF_CONVENTIONAL_MAC 1
#define SICSLOWPAN_CONF_MAX_ADDR_CONTEXTS 2
#else /* WITH_UIP6 */
#define UIP_CONF_IP_FORWARD 1
#define UIP_CONF_BUFFER_SIZE 1300
#endif /* WITH_UIP6 */
#define UIP_CONF_ICMP_DEST_UNREACH 1
#define UIP_CONF_DHCP_LIGHT
#define UIP_CONF_LLH_LEN 0
#define UIP_CONF_RECEIVE_WINDOW 48
#define UIP_CONF_TCP_MSS 48
#define UIP_CONF_MAX_CONNECTIONS 4
#define UIP_CONF_MAX_LISTENPORTS 8
#define UIP_CONF_UDP_CONNS 12
#define UIP_CONF_FWCACHE_SIZE 30
#define UIP_CONF_BROADCAST 1
#define UIP_CONF_UDP 1
#define UIP_CONF_UDP_CHECKSUMS 1
#define UIP_CONF_PINGADDRCONF 0
#define UIP_CONF_LOGGING 0
#define UIP_CONF_TCP_SPLIT 0
/* include the project config */
/* PROJECT_CONF_H might be defined in the project Makefile */
#ifdef PROJECT_CONF_H
#include PROJECT_CONF_H
#endif /* PROJECT_CONF_H */
#endif /* __CONTIKI_CONF_H__ */

View File

@ -0,0 +1,258 @@
/*
* Copyright (c) 2014, Analog Devices, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* 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 HOLDER 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 Ian Martin <martini@redwirellc.com>
*/
#include <stdbool.h>
#include <stdio.h>
#include <string.h>
#include "contiki.h"
#include "net/netstack.h"
#include "dev/serial-line.h"
#include "net/uip.h"
#include "dev/button-sensor.h"
#if WITH_UIP6
#include "net/uip-ds6.h"
#endif /* WITH_UIP6 */
#include "net/rime.h"
#include "uart0.h"
#include "contiki-uart.h"
#include "watchdog.h"
#include "slip-arch.h"
#if __GNUC__
#include "write.h"
#endif
SENSORS(&button_sensor);
#ifndef SERIAL_ID
#define SERIAL_ID { 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08 }
#endif
static uint8_t serial_id[] = SERIAL_ID;
static uint16_t node_id = 0x0102;
/*---------------------------------------------------------------------------*/
static void
set_rime_addr(void)
{
rimeaddr_t addr;
int i;
memset(&addr, 0, sizeof(rimeaddr_t));
#if UIP_CONF_IPV6
memcpy(addr.u8, serial_id, sizeof(addr.u8));
#else
if(node_id == 0) {
for(i = 0; i < sizeof(rimeaddr_t); ++i) {
addr.u8[i] = serial_id[7 - i];
}
} else {
addr.u8[0] = node_id & 0xff;
addr.u8[1] = node_id >> 8;
}
#endif
rimeaddr_set_node_addr(&addr);
printf("Rime started with address ");
for(i = 0; i < sizeof(addr.u8) - 1; i++) {
printf("%d.", addr.u8[i]);
}
printf("%d" NEWLINE, addr.u8[i]);
}
/*---------------------------------------------------------------------------*/
int contiki_argc = 0;
char **contiki_argv;
static void
delay_1sec(void)
{
/* Delay 1 second */
register unsigned long int i;
for(i = 0x000FFFFFUL; i; --i) {
asm ("nop");
}
}
int
main(int argc, char **argv)
{
bool flip_flop = false;
asm ("di");
/* Setup clocks */
CMC = 0x11U; /* Enable XT1, disable X1 */
CSC = 0x80U; /* Start XT1 and HOCO, stop X1 */
CKC = 0x00U;
delay_1sec();
OSMC = 0x00; /* Supply fsub to peripherals, including Interval Timer */
uart0_init();
#if __GNUC__
/* Force linking of custom write() function: */
write(1, NULL, 0);
#endif
/* Setup 12-bit interval timer */
RTCEN = 1; /* Enable 12-bit interval timer and RTC */
ITMK = 1; /* Disable IT interrupt */
ITPR0 = 0; /* Set interrupt priority - highest */
ITPR1 = 0;
ITMC = 0x8FFFU; /* Set maximum period 4096/32768Hz = 1/8 s, and start timer */
ITIF = 0; /* Clear interrupt request flag */
ITMK = 0; /* Enable IT interrupt */
/* asm ("ei"); / * Enable interrupts * / */
/* Disable analog inputs because they can conflict with the SPI buses: */
ADPC = 0x01; /* Configure all analog pins as digital I/O. */
PMC0 &= 0xF0; /* Disable analog inputs. */
clock_init();
/* Initialize Joystick Inputs: */
PM5 |= BIT(5) | BIT(4) | BIT(3) | BIT(2) | BIT(1); /* Set pins as inputs. */
PU5 |= BIT(5) | BIT(4) | BIT(3) | BIT(2) | BIT(1); /* Enable internal pull-up resistors. */
/* Initialize LED outputs: */
#define BIT(n) (1 << (n))
PM12 &= ~BIT(0); /* LED1 */
PM4 &= ~BIT(3); /* LED2 */
PM1 &= ~BIT(6); /* LED3 */
PM1 &= ~BIT(5); /* LED4 */
PM0 &= ~BIT(6); /* LED5 */
PM0 &= ~BIT(5); /* LED6 */
PM3 &= ~BIT(0); /* LED7 */
PM5 &= ~BIT(0); /* LED8 */
#if UIP_CONF_IPV6
#if UIP_CONF_IPV6_RPL
printf(CONTIKI_VERSION_STRING " started with IPV6, RPL" NEWLINE);
#else
printf(CONTIKI_VERSION_STRING " started with IPV6" NEWLINE);
#endif
#else
printf(CONTIKI_VERSION_STRING " started" NEWLINE);
#endif
/* crappy way of remembering and accessing argc/v */
contiki_argc = argc;
contiki_argv = argv;
process_init();
process_start(&etimer_process, NULL);
ctimer_init();
set_rime_addr();
queuebuf_init();
netstack_init();
printf("MAC %s RDC %s NETWORK %s" NEWLINE, NETSTACK_MAC.name, NETSTACK_RDC.name, NETSTACK_NETWORK.name);
#if WITH_UIP6
memcpy(&uip_lladdr.addr, serial_id, sizeof(uip_lladdr.addr));
process_start(&tcpip_process, NULL);
printf("Tentative link-local IPv6 address ");
{
uip_ds6_addr_t *lladdr;
int i;
lladdr = uip_ds6_get_link_local(-1);
for(i = 0; i < 7; ++i) {
printf("%02x%02x:", lladdr->ipaddr.u8[i * 2],
lladdr->ipaddr.u8[i * 2 + 1]);
}
/* make it hardcoded... */
lladdr->state = ADDR_AUTOCONF;
printf("%02x%02x" NEWLINE, lladdr->ipaddr.u8[14], lladdr->ipaddr.u8[15]);
}
#else
process_start(&tcpip_process, NULL);
#endif
serial_line_init();
autostart_start(autostart_processes);
while(1) {
watchdog_periodic();
if(NETSTACK_RADIO.pending_packet()) {
int len;
packetbuf_clear();
len = NETSTACK_RADIO.read(packetbuf_dataptr(), PACKETBUF_SIZE);
if(len > 0) {
packetbuf_set_datalen(len);
NETSTACK_RDC.input();
}
}
while(uart0_can_getchar()) {
char c;
UART_RX_LED = 1;
c = uart0_getchar();
if(uart0_input_handler) {
uart0_input_handler(c);
}
}
UART_RX_LED = 0;
process_run();
etimer_request_poll();
HEARTBEAT_LED1 = flip_flop;
flip_flop = !flip_flop;
HEARTBEAT_LED2 = flip_flop;
}
return 0;
}
/*---------------------------------------------------------------------------*/
void
log_message(char *m1, char *m2)
{
printf("%s%s" NEWLINE, m1, m2);
}
/*---------------------------------------------------------------------------*/
void
uip_log(char *m)
{
printf("%s" NEWLINE, m);
}
/*---------------------------------------------------------------------------*/

View File

@ -0,0 +1,58 @@
/*
* Copyright (c) 2014, Analog Devices, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* 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 HOLDER 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 Ian Martin <martini@redwirellc.com>
*/
#ifndef NEWLINE
#define NEWLINE "\r\n"
#endif
#ifndef BIT
#define BIT(n) (1 << (n))
#endif
#define BAUD2UBR(x) (x)
#define LED1 P120
#define LED2 P43
#define LED3 P16
#define LED4 P15
#define LED5 P06
#define LED6 P05
#define LED7 P30
#define LED8 P50
#define HEARTBEAT_LED1 LED2
#define HEARTBEAT_LED2 LED3
#define RADIO_TX_LED LED5
#define RADIO_RX_LED LED6
#define UART_RX_LED LED8

View File

@ -4,6 +4,7 @@ TOOLSDIR=../../tools
EXAMPLES = \
hello-world/avr-raven \
hello-world/exp5438 \
hello-world/eval-adf7xxxmb4z \
hello-world/micaz \
hello-world/minimal-net \
hello-world/native \
@ -29,6 +30,7 @@ sky-shell-webserver/sky \
telnet-server/minimal-net \
webserver/minimal-net \
webserver-ipv6/exp5438 \
webserver-ipv6/eval-adf7xxxmb4z \
wget/minimal-net \
z1/z1 \
settings-example/avr-raven \