Merge branch 'contiki'

Conflicts:
	cpu/cc26xx-cc13xx/lib/cc13xxware
	cpu/cc26xx-cc13xx/lib/cc26xxware
This commit is contained in:
Harald Pichler 2017-01-31 15:00:59 +01:00
commit 2f8549aaae
319 changed files with 58114 additions and 6745 deletions

View file

@ -31,6 +31,8 @@
# Author: Oliver Schmidt <ol.sc@web.de>
#
DEFINES += STATIC_DRIVER=cs8900a
CONTIKI_CPU = $(CONTIKI)/cpu/6502
include $(CONTIKI_CPU)/Makefile.6502
@ -53,7 +55,6 @@ disk: all
cp $(CONTIKI)/tools/$(TARGET)/dos25/dup.sys atr/dup.sys
cp $(CONTIKI_PROJECT).$(TARGET) atr/autorun.sys
cp $(CONTIKI)/tools/$(TARGET)/sample.cfg atr/contiki.cfg
cp cs8900a.eth atr/cs8900a.eth
ifeq ($(findstring WITH_MOUSE,$(DEFINES)),WITH_MOUSE)
cp $(CC65_TARGET_DIR)/drv/mou/atrxst.mou atr/contiki.mou
endif

View file

@ -434,7 +434,9 @@ typedef unsigned short uip_stats_t;
#undef UIP_CONF_TCP
#define UIP_CONF_TCP 1
#define UIP_CONF_TCP_MSS 48
#ifndef UIP_CONF_RECEIVE_WINDOW
#define UIP_CONF_RECEIVE_WINDOW 48
#endif
#undef NBR_TABLE_CONF_MAX_NEIGHBORS
#define NBR_TABLE_CONF_MAX_NEIGHBORS 5
#undef UIP_CONF_MAX_ROUTES

View file

@ -10,6 +10,7 @@ CONTIKI_TARGET_SOURCEFILES += temp-sensor.c
CONTIKI_TARGET_SOURCEFILES += enc28j60_avr.c
CONTIKI_TARGET_SOURCEFILES += co2_sa_kxx-sensor.c
CONTIKI_TARGET_SOURCEFILES += bme280-arch.c
CONTIKIAVR=$(CONTIKI)/cpu/avr
CONTIKIBOARD=.

View file

@ -376,7 +376,7 @@ initialize(void)
#if 0
{
uip_ip6addr_t ipaddr;
uip_ip6addr(&ipaddr, 0xaaaa, 0, 0, 0, 0, 0, 0, 0);
uip_ip6addr(&ipaddr, 0xfd00, 0, 0, 0, 0, 0, 0, 0);
uip_ds6_addr_add(&ipaddr, 0, ADDR_AUTOCONF);
/* uip_ds6_prefix_add(&ipaddr,64,0); */
}

View file

@ -0,0 +1,51 @@
/*
* Copyright (c) 2016, Zolertia
* 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.
*/
/*---------------------------------------------------------------------------*/
#include "contiki.h"
#include "i2c.h"
/*---------------------------------------------------------------------------*/
void
bme280_arch_i2c_init(void)
{
/* Does nothing */
}
/*---------------------------------------------------------------------------*/
void
bme280_arch_i2c_write_mem(uint8_t addr, uint8_t reg, uint8_t value)
{
i2c_write_mem(addr, reg, value);
}
/*---------------------------------------------------------------------------*/
void
bme280_arch_i2c_read_mem(uint8_t addr, uint8_t reg, uint8_t *buf, uint8_t bytes)
{
i2c_read_mem(addr, reg, buf, bytes);
}

View file

@ -224,5 +224,11 @@ i2c_probe(void)
probed |= I2C_CO2SA;
print_delim(p++, "CO2SA", del);
}
watchdog_periodic();
if(!i2c_start(I2C_BME280_ADDR)) {
i2c_stop();
probed |= I2C_BME280;
print_delim(p++, "BME280", del);
}
return probed;
}

View file

@ -40,12 +40,13 @@
/* Here we define the i2c address for dev we support */
#define I2C_AT24MAC_ADDR 0xB0 /* EUI64 ADDR */
#define I2C_SHT2X_ADDR (0x40 << 1) /* SHT2X ADDR */
#define I2C_BME280_ADDR (0x77 << 1) /* Alternative 0x76 */
/* Here we define a enumration for devices */
#define I2C_AT24MAC (1<<0)
#define I2C_SHT2X (1<<1)
#define I2C_CO2SA (1<<2) /* Sense-Air CO2 */
#define I2C_BME280 (1<<3)
#define I2C_READ 1
#define I2C_WRITE 0

View file

@ -7,7 +7,7 @@ CONTIKI_TARGET_MAIN = ${CONTIKI_CORE}.o
CONTIKI_TARGET_SOURCEFILES += rs232.c cfs-eeprom.c eeprom.c random.c mmem.c \
contiki-avr-zigbit-main.c \
sicslowmac.c linkaddr.c queuebuf.c nullmac.c packetbuf.c \
frame802154.c framer-802154.c framer.c nullsec.c nbr-table.c
frame802154.c framer-802154.c nullsec.c nbr-table.c
CONTIKIAVR = $(CONTIKI)/cpu/avr
CONTIKIBOARD = .
@ -17,4 +17,5 @@ CONTIKI_PLAT_DEFS = -DF_CPU=8000000UL -DAUTO_CRC_PADDING=2
MCU = atmega1281
include $(CONTIKIAVR)/Makefile.avr
include $(CONTIKIAVR)/radio/Makefile.radio
include $(CONTIKIAVR)/radio/Makefile.radio
MODULES += core/net

View file

@ -186,6 +186,10 @@
#define IEEE802154_CONF_PANID 0xABCD
#endif
#ifdef RF_CHANNEL
#define CC2530_RF_CONF_CHANNEL RF_CHANNEL
#endif
#ifndef CC2530_RF_CONF_CHANNEL
#define CC2530_RF_CONF_CHANNEL 25
#endif /* CC2530_RF_CONF_CHANNEL */
@ -216,10 +220,6 @@
#define UIP_CONF_IP_FORWARD 0
#define RPL_CONF_STATS 0
#ifndef RPL_CONF_OF
#define RPL_CONF_OF rpl_mrhof
#endif
#define UIP_CONF_ND6_REACHABLE_TIME 600000
#define UIP_CONF_ND6_RETRANS_TIMER 10000

View file

@ -364,6 +364,10 @@ typedef uint32_t rtimer_clock_t;
#define IEEE802154_CONF_PANID 0xABCD
#endif
#ifdef RF_CHANNEL
#define CC2538_RF_CONF_CHANNEL RF_CHANNEL
#endif
#ifndef CC2538_RF_CONF_CHANNEL
#define CC2538_RF_CONF_CHANNEL 25
#endif /* CC2538_RF_CONF_CHANNEL */
@ -420,10 +424,6 @@ typedef uint32_t rtimer_clock_t;
#define UIP_CONF_IP_FORWARD 0
#define RPL_CONF_STATS 0
#ifndef RPL_CONF_OF
#define RPL_CONF_OF rpl_mrhof
#endif
#define UIP_CONF_ND6_REACHABLE_TIME 600000
#define UIP_CONF_ND6_RETRANS_TIMER 10000

View file

@ -46,7 +46,6 @@
#include "dev/adc.h"
#include "dev/leds.h"
#include "dev/sys-ctrl.h"
#include "dev/scb.h"
#include "dev/nvic.h"
#include "dev/uart.h"
#include "dev/watchdog.h"

View file

@ -141,27 +141,27 @@
/** BUTTON_SELECT -> PA3 */
#define BUTTON_SELECT_PORT GPIO_A_NUM
#define BUTTON_SELECT_PIN 3
#define BUTTON_SELECT_VECTOR NVIC_INT_GPIO_PORT_A
#define BUTTON_SELECT_VECTOR GPIO_A_IRQn
/** BUTTON_LEFT -> PC4 */
#define BUTTON_LEFT_PORT GPIO_C_NUM
#define BUTTON_LEFT_PIN 4
#define BUTTON_LEFT_VECTOR NVIC_INT_GPIO_PORT_C
#define BUTTON_LEFT_VECTOR GPIO_C_IRQn
/** BUTTON_RIGHT -> PC5 */
#define BUTTON_RIGHT_PORT GPIO_C_NUM
#define BUTTON_RIGHT_PIN 5
#define BUTTON_RIGHT_VECTOR NVIC_INT_GPIO_PORT_C
#define BUTTON_RIGHT_VECTOR GPIO_C_IRQn
/** BUTTON_UP -> PC6 */
#define BUTTON_UP_PORT GPIO_C_NUM
#define BUTTON_UP_PIN 6
#define BUTTON_UP_VECTOR NVIC_INT_GPIO_PORT_C
#define BUTTON_UP_VECTOR GPIO_C_IRQn
/** BUTTON_DOWN -> PC7 */
#define BUTTON_DOWN_PORT GPIO_C_NUM
#define BUTTON_DOWN_PIN 7
#define BUTTON_DOWN_VECTOR NVIC_INT_GPIO_PORT_C
#define BUTTON_DOWN_VECTOR GPIO_C_IRQn
/* Notify various examples that we have Buttons */
#define PLATFORM_HAS_BUTTON 1

View file

@ -135,7 +135,7 @@ config_select(int type, int value)
ioc_set_over(BUTTON_SELECT_PORT, BUTTON_SELECT_PIN, IOC_OVERRIDE_PUE);
nvic_interrupt_enable(BUTTON_SELECT_VECTOR);
NVIC_EnableIRQ(BUTTON_SELECT_VECTOR);
gpio_register_callback(btn_callback, BUTTON_SELECT_PORT, BUTTON_SELECT_PIN);
return 1;
@ -159,7 +159,7 @@ config_left(int type, int value)
ioc_set_over(BUTTON_LEFT_PORT, BUTTON_LEFT_PIN, IOC_OVERRIDE_PUE);
nvic_interrupt_enable(BUTTON_LEFT_VECTOR);
NVIC_EnableIRQ(BUTTON_LEFT_VECTOR);
gpio_register_callback(btn_callback, BUTTON_LEFT_PORT, BUTTON_LEFT_PIN);
return 1;
@ -183,7 +183,7 @@ config_right(int type, int value)
ioc_set_over(BUTTON_RIGHT_PORT, BUTTON_RIGHT_PIN, IOC_OVERRIDE_PUE);
nvic_interrupt_enable(BUTTON_RIGHT_VECTOR);
NVIC_EnableIRQ(BUTTON_RIGHT_VECTOR);
gpio_register_callback(btn_callback, BUTTON_RIGHT_PORT, BUTTON_RIGHT_PIN);
return 1;
@ -207,7 +207,7 @@ config_up(int type, int value)
ioc_set_over(BUTTON_UP_PORT, BUTTON_UP_PIN, IOC_OVERRIDE_PUE);
nvic_interrupt_enable(BUTTON_UP_VECTOR);
NVIC_EnableIRQ(BUTTON_UP_VECTOR);
gpio_register_callback(btn_callback, BUTTON_UP_PORT, BUTTON_UP_PIN);
return 1;
@ -231,7 +231,7 @@ config_down(int type, int value)
ioc_set_over(BUTTON_DOWN_PORT, BUTTON_DOWN_PIN, IOC_OVERRIDE_PUE);
nvic_interrupt_enable(BUTTON_DOWN_VECTOR);
NVIC_EnableIRQ(BUTTON_DOWN_VECTOR);
gpio_register_callback(btn_callback, BUTTON_DOWN_PORT, BUTTON_DOWN_PIN);
return 1;

View file

@ -376,9 +376,6 @@ Java_org_contikios_cooja_corecomm_CLASSNAME_setMemory(JNIEnv *env, jobject obj,
JNIEXPORT void JNICALL
Java_org_contikios_cooja_corecomm_CLASSNAME_tick(JNIEnv *env, jobject obj)
{
clock_time_t nextEtimer;
rtimer_clock_t nextRtimer;
simProcessRunValue = 0;
/* Let all simulation interfaces act first */
@ -403,21 +400,11 @@ Java_org_contikios_cooja_corecomm_CLASSNAME_tick(JNIEnv *env, jobject obj)
doActionsAfterTick();
/* Do we have any pending timers */
simEtimerPending = etimer_pending() || rtimer_arch_pending();
if(!simEtimerPending) {
return;
}
simEtimerPending = etimer_pending();
/* Save nearest expiration time */
nextEtimer = etimer_next_expiration_time() - (clock_time_t) simCurrentTime;
nextRtimer = rtimer_arch_next() - (rtimer_clock_t) simCurrentTime;
if(etimer_pending() && rtimer_arch_pending()) {
simNextExpirationTime = MIN(nextEtimer, nextRtimer);
} else if(etimer_pending()) {
simNextExpirationTime = nextEtimer;
} else if(rtimer_arch_pending()) {
simNextExpirationTime = nextRtimer;
}
simEtimerNextExpirationTime = etimer_next_expiration_time();
}
/*---------------------------------------------------------------------------*/
/**

View file

@ -200,8 +200,12 @@ typedef unsigned short uip_stats_t;
#define CLOCK_CONF_SECOND 1000L
typedef unsigned long clock_time_t;
typedef unsigned long rtimer_clock_t;
#define RTIMER_CLOCK_DIFF(a,b) ((signed long)((a)-(b)))
typedef uint64_t rtimer_clock_t;
#define RTIMER_CLOCK_DIFF(a,b) ((int64_t)((a)-(b)))
#define RADIO_DELAY_BEFORE_TX 0
#define RADIO_DELAY_BEFORE_RX 0
#define RADIO_DELAY_BEFORE_DETECT 0
#define AODV_COMPLIANCE
#define AODV_NUM_RT_ENTRIES 32

View file

@ -452,9 +452,6 @@ Java_org_contikios_cooja_corecomm_CLASSNAME_setMemory(JNIEnv *env, jobject obj,
JNIEXPORT void JNICALL
Java_org_contikios_cooja_corecomm_CLASSNAME_tick(JNIEnv *env, jobject obj)
{
clock_time_t nextEtimer;
rtimer_clock_t nextRtimer;
simProcessRunValue = 0;
/* Let all simulation interfaces act first */
@ -479,21 +476,11 @@ Java_org_contikios_cooja_corecomm_CLASSNAME_tick(JNIEnv *env, jobject obj)
doActionsAfterTick();
/* Do we have any pending timers */
simEtimerPending = etimer_pending() || rtimer_arch_pending();
if(!simEtimerPending) {
return;
}
simEtimerPending = etimer_pending();
/* Save nearest expiration time */
nextEtimer = etimer_next_expiration_time() - (clock_time_t) simCurrentTime;
nextRtimer = rtimer_arch_next() - (rtimer_clock_t) simCurrentTime;
if(etimer_pending() && rtimer_arch_pending()) {
simNextExpirationTime = MIN(nextEtimer, nextRtimer);
} else if(etimer_pending()) {
simNextExpirationTime = nextEtimer;
} else if(rtimer_arch_pending()) {
simNextExpirationTime = nextRtimer;
}
simEtimerNextExpirationTime = etimer_next_expiration_time();
}
/*---------------------------------------------------------------------------*/
/**

View file

@ -46,15 +46,13 @@
#define COOJA_RADIO_BUFSIZE PACKETBUF_SIZE
#define CCA_SS_THRESHOLD -95
#define WITH_TURNAROUND 1
#define WITH_SEND_CCA 1
const struct simInterface radio_interface;
/* COOJA */
char simReceiving = 0;
char simInDataBuffer[COOJA_RADIO_BUFSIZE];
int simInSize = 0;
rtimer_clock_t simLastPacketTimestamp = 0;
char simOutDataBuffer[COOJA_RADIO_BUFSIZE];
int simOutSize = 0;
char simRadioHWOn = 1;
@ -66,8 +64,37 @@ int simLQI = 105;
static const void *pending_data;
PROCESS(cooja_radio_process, "cooja radio process");
/* If we are in the polling mode, poll_mode is 1; otherwise 0 */
static int poll_mode = 0; /* default 0, disabled */
static int auto_ack = 0; /* AUTO_ACK is not supported; always 0 */
static int addr_filter = 0; /* ADDRESS_FILTER is not supported; always 0 */
static int send_on_cca = (COOJA_TRANSMIT_ON_CCA != 0);
PROCESS(cooja_radio_process, "cooja radio process");
/*---------------------------------------------------------------------------*/
static void
set_send_on_cca(uint8_t enable)
{
send_on_cca = enable;
}
/*---------------------------------------------------------------------------*/
static void
set_frame_filtering(int enable)
{
addr_filter = enable;
}
/*---------------------------------------------------------------------------*/
static void
set_auto_ack(int enable)
{
auto_ack = enable;
}
/*---------------------------------------------------------------------------*/
static void
set_poll_mode(int enable)
{
poll_mode = enable;
}
/*---------------------------------------------------------------------------*/
void
radio_set_channel(int channel)
@ -97,7 +124,7 @@ radio_signal_strength_current(void)
int
radio_LQI(void)
{
return simLQI;
return simLQI;
}
/*---------------------------------------------------------------------------*/
static int
@ -152,8 +179,10 @@ radio_read(void *buf, unsigned short bufsize)
memcpy(buf, simInDataBuffer, simInSize);
simInSize = 0;
packetbuf_set_attr(PACKETBUF_ATTR_RSSI, simSignalStrength);
packetbuf_set_attr(PACKETBUF_ATTR_LINK_QUALITY, simLQI);
if(!poll_mode) {
packetbuf_set_attr(PACKETBUF_ATTR_RSSI, simSignalStrength);
packetbuf_set_attr(PACKETBUF_ATTR_LINK_QUALITY, simLQI);
}
return tmp;
}
@ -173,14 +202,14 @@ radio_send(const void *payload, unsigned short payload_len)
int radiostate = simRadioHWOn;
/* Simulate turnaround time of 2ms for packets, 1ms for acks*/
#if WITH_TURNAROUND
#if COOJA_SIMULATE_TURNAROUND
simProcessRunValue = 1;
cooja_mt_yield();
if(payload_len > 3) {
simProcessRunValue = 1;
cooja_mt_yield();
}
#endif /* WITH_TURNAROUND */
#endif /* COOJA_SIMULATE_TURNAROUND */
if(!simRadioHWOn) {
/* Turn on radio temporarily */
@ -197,11 +226,11 @@ radio_send(const void *payload, unsigned short payload_len)
}
/* Transmit on CCA */
#if WITH_SEND_CCA
if(!channel_clear()) {
#if COOJA_TRANSMIT_ON_CCA
if(send_on_cca && !channel_clear()) {
return RADIO_TX_COLLISION;
}
#endif /* WITH_SEND_CCA */
#endif /* COOJA_TRANSMIT_ON_CCA */
/* Copy packet data to temporary storage */
memcpy(simOutDataBuffer, payload, payload_len);
@ -253,6 +282,9 @@ PROCESS_THREAD(cooja_radio_process, ev, data)
while(1) {
PROCESS_YIELD_UNTIL(ev == PROCESS_EVENT_POLL);
if(poll_mode) {
continue;
}
packetbuf_clear();
len = radio_read(packetbuf_dataptr(), PACKETBUF_SIZE);
@ -275,18 +307,87 @@ init(void)
static radio_result_t
get_value(radio_param_t param, radio_value_t *value)
{
return RADIO_RESULT_NOT_SUPPORTED;
switch(param) {
case RADIO_PARAM_RX_MODE:
*value = 0;
if(addr_filter) {
*value |= RADIO_RX_MODE_ADDRESS_FILTER;
}
if(auto_ack) {
*value |= RADIO_RX_MODE_AUTOACK;
}
if(poll_mode) {
*value |= RADIO_RX_MODE_POLL_MODE;
}
return RADIO_RESULT_OK;
case RADIO_PARAM_TX_MODE:
*value = 0;
if(send_on_cca) {
*value |= RADIO_TX_MODE_SEND_ON_CCA;
}
return RADIO_RESULT_OK;
case RADIO_PARAM_LAST_RSSI:
*value = simSignalStrength;
return RADIO_RESULT_OK;
case RADIO_PARAM_LAST_LINK_QUALITY:
*value = simLQI;
return RADIO_RESULT_OK;
default:
return RADIO_RESULT_NOT_SUPPORTED;
}
}
/*---------------------------------------------------------------------------*/
static radio_result_t
set_value(radio_param_t param, radio_value_t value)
{
return RADIO_RESULT_NOT_SUPPORTED;
switch(param) {
case RADIO_PARAM_RX_MODE:
if(value & ~(RADIO_RX_MODE_ADDRESS_FILTER |
RADIO_RX_MODE_AUTOACK | RADIO_RX_MODE_POLL_MODE)) {
return RADIO_RESULT_INVALID_VALUE;
}
/* Only disabling is acceptable for RADIO_RX_MODE_ADDRESS_FILTER */
if ((value & RADIO_RX_MODE_ADDRESS_FILTER) != 0) {
return RADIO_RESULT_NOT_SUPPORTED;
}
set_frame_filtering((value & RADIO_RX_MODE_ADDRESS_FILTER) != 0);
/* Only disabling is acceptable for RADIO_RX_MODE_AUTOACK */
if ((value & RADIO_RX_MODE_ADDRESS_FILTER) != 0) {
return RADIO_RESULT_NOT_SUPPORTED;
}
set_auto_ack((value & RADIO_RX_MODE_AUTOACK) != 0);
set_poll_mode((value & RADIO_RX_MODE_POLL_MODE) != 0);
return RADIO_RESULT_OK;
case RADIO_PARAM_TX_MODE:
if(value & ~(RADIO_TX_MODE_SEND_ON_CCA)) {
return RADIO_RESULT_INVALID_VALUE;
}
set_send_on_cca((value & RADIO_TX_MODE_SEND_ON_CCA) != 0);
return RADIO_RESULT_OK;
case RADIO_PARAM_CHANNEL:
if(value < 11 || value > 26) {
return RADIO_RESULT_INVALID_VALUE;
}
radio_set_channel(value);
return RADIO_RESULT_OK;
default:
return RADIO_RESULT_NOT_SUPPORTED;
}
}
/*---------------------------------------------------------------------------*/
static radio_result_t
get_object(radio_param_t param, void *dest, size_t size)
{
if(param == RADIO_PARAM_LAST_PACKET_TIMESTAMP) {
if(size != sizeof(rtimer_clock_t) || !dest) {
return RADIO_RESULT_INVALID_VALUE;
}
*(rtimer_clock_t *)dest = (rtimer_clock_t)simLastPacketTimestamp;
return RADIO_RESULT_OK;
}
return RADIO_RESULT_NOT_SUPPORTED;
}
/*---------------------------------------------------------------------------*/
@ -315,5 +416,5 @@ const struct radio_driver cooja_radio_driver =
};
/*---------------------------------------------------------------------------*/
SIM_INTERFACE(radio_interface,
doInterfaceActionsBeforeTick,
doInterfaceActionsAfterTick);
doInterfaceActionsBeforeTick,
doInterfaceActionsAfterTick);

View file

@ -36,6 +36,18 @@
#include "contiki.h"
#include "dev/radio.h"
#ifdef COOJA_CONF_SIMULATE_TURNAROUND
#define COOJA_SIMULATE_TURNAROUND COOJA_CONF_SIMULATE_TURNAROUND
#else
#define COOJA_SIMULATE_TURNAROUND 1
#endif
#ifdef COOJA_CONF_TRANSMIT_ON_CCA
#define COOJA_TRANSMIT_ON_CCA COOJA_CONF_TRANSMIT_ON_CCA
#else
#define COOJA_TRANSMIT_ON_CCA 1
#endif
extern const struct radio_driver cooja_radio_driver;
/**

View file

@ -40,7 +40,7 @@ char simDontFallAsleep = 0;
int simProcessRunValue;
int simEtimerPending;
clock_time_t simNextExpirationTime;
clock_time_t simEtimerNextExpirationTime;
void doActionsBeforeTick() {
// Poll all interfaces to do their thing before the tick

View file

@ -42,7 +42,7 @@ struct simInterface {
// Variable for keeping the last process_run() return value
extern int simProcessRunValue;
extern int simEtimerPending;
extern clock_time_t simNextExpirationTime;
extern clock_time_t simEtimerNextExpirationTime;
extern clock_time_t simCurrentTime;
// Variable that when set to != 0, stops the mote from falling asleep next tick

View file

@ -48,46 +48,44 @@
#define PRINTF(...)
#endif
extern clock_time_t simCurrentTime;
static int pending_rtimer = 0;
static rtimer_clock_t next_rtimer = 0;
static clock_time_t last_rtimer_now = 0;
/* COOJA */
int simRtimerPending;
rtimer_clock_t simRtimerNextExpirationTime;
rtimer_clock_t simRtimerCurrentTicks;
/*---------------------------------------------------------------------------*/
void
rtimer_arch_init(void)
{
next_rtimer = 0;
last_rtimer_now = 0;
pending_rtimer = 0;
simRtimerNextExpirationTime = 0;
simRtimerPending = 0;
}
/*---------------------------------------------------------------------------*/
void
rtimer_arch_schedule(rtimer_clock_t t)
{
next_rtimer = t;
pending_rtimer = 1;
simRtimerNextExpirationTime = t;
simRtimerPending = 1;
}
/*---------------------------------------------------------------------------*/
rtimer_clock_t
rtimer_arch_next(void)
{
return next_rtimer;
return simRtimerNextExpirationTime;
}
/*---------------------------------------------------------------------------*/
int
rtimer_arch_pending(void)
{
return pending_rtimer;
return simRtimerPending;
}
/*---------------------------------------------------------------------------*/
int
rtimer_arch_check(void)
{
if (simCurrentTime == next_rtimer) {
if (simRtimerCurrentTicks == simRtimerNextExpirationTime) {
/* Execute rtimer */
pending_rtimer = 0;
simRtimerPending = 0;
rtimer_run_next();
return 1;
}
@ -97,14 +95,7 @@ rtimer_arch_check(void)
rtimer_clock_t
rtimer_arch_now(void)
{
if(last_rtimer_now == simCurrentTime) {
/* Yield to COOJA, to allow time to change */
simProcessRunValue = 1;
simNextExpirationTime = simCurrentTime + 1;
cooja_mt_yield();
}
last_rtimer_now = simCurrentTime;
return simCurrentTime;
return simRtimerCurrentTicks;
}
/*---------------------------------------------------------------------------*/

View file

@ -36,7 +36,11 @@
#include "contiki-conf.h"
#include "sys/clock.h"
#define RTIMER_ARCH_SECOND CLOCK_CONF_SECOND
#define RTIMER_ARCH_SECOND UINT64_C(1000000)
#define US_TO_RTIMERTICKS(US) (US)
#define RTIMERTICKS_TO_US(T) (T)
#define RTIMERTICKS_TO_US_64(T) (T)
rtimer_clock_t rtimer_arch_now(void);
int rtimer_arch_check(void);

View file

@ -212,7 +212,9 @@
#define UIP_CONF_DHCP_LIGHT
#define UIP_CONF_LLH_LEN 0
#ifndef UIP_CONF_RECEIVE_WINDOW
#define UIP_CONF_RECEIVE_WINDOW 48
#endif
#define UIP_CONF_TCP_MSS 48
#define UIP_CONF_MAX_CONNECTIONS 4
#define UIP_CONF_MAX_LISTENPORTS 8

View file

@ -159,7 +159,9 @@
#define UIP_CONF_DHCP_LIGHT
#define UIP_CONF_LLH_LEN 0
#ifndef UIP_CONF_RECEIVE_WINDOW
#define UIP_CONF_RECEIVE_WINDOW 48
#endif
#define UIP_CONF_TCP_MSS 48
#define UIP_CONF_MAX_CONNECTIONS 4
#define UIP_CONF_MAX_LISTENPORTS 4

View file

@ -162,7 +162,9 @@
#define UIP_CONF_DHCP_LIGHT
#define UIP_CONF_LLH_LEN 0
#ifndef UIP_CONF_RECEIVE_WINDOW
#define UIP_CONF_RECEIVE_WINDOW 48
#endif
#define UIP_CONF_TCP_MSS 48
#define UIP_CONF_MAX_CONNECTIONS 4
#define UIP_CONF_MAX_LISTENPORTS 8

View file

@ -76,6 +76,14 @@ app_main(void)
halt();
}
/*---------------------------------------------------------------------------*/
static void
gp_fault_handler(struct interrupt_context context)
{
fprintf(stderr, "General protection exception @%08x (ec: %u)\n",
context.eip, context.error_code);
halt();
}
/*---------------------------------------------------------------------------*/
/* Kernel entrypoint */
int
main(void)
@ -91,6 +99,7 @@ main(void)
* Galileo Gen2 FTDI header
*/
quarkX1000_uart_init_port(QUARK_X1000_UART_1, 115200);
SET_EXCEPTION_HANDLER(13, 1, gp_fault_handler);
clock_init();
rtimer_init();

View file

@ -53,6 +53,10 @@
#define MIRCOMAC_CONF_BUF_NUM 2
#endif
#ifdef RF_CHANNEL
#define MICROMAC_CONF_CHANNEL RF_CHANNEL
#endif
#ifndef MICROMAC_CONF_CHANNEL
#define MICROMAC_CONF_CHANNEL 26
#endif

View file

@ -179,7 +179,9 @@
#define UIP_CONF_DHCP_LIGHT
#define UIP_CONF_LLH_LEN 0
#ifndef UIP_CONF_RECEIVE_WINDOW
#define UIP_CONF_RECEIVE_WINDOW 48
#endif
#define UIP_CONF_TCP_MSS 48
#define UIP_CONF_MAX_CONNECTIONS 4
#define UIP_CONF_MAX_LISTENPORTS 8

View file

@ -64,7 +64,6 @@ typedef int32_t s32_t;
typedef unsigned short uip_stats_t;
#if NETSTACK_CONF_WITH_IPV6
/* The Windows build uses wpcap to connect to a host interface. It finds the interface by scanning for
* an address, which can be specified here and overridden with the command line.
@ -148,6 +147,7 @@ typedef unsigned short uip_stats_t;
#endif
#define UIP_CONF_LLH_LEN 14
#define LINKADDR_CONF_SIZE 6
#define UIP_CONF_MAX_LISTENPORTS 40
#define UIP_CONF_MAX_CONNECTIONS 40
#define UIP_CONF_BYTE_ORDER UIP_LITTLE_ENDIAN

View file

@ -141,7 +141,9 @@ typedef unsigned short uip_stats_t;
#define UIP_CONF_ICMP_DEST_UNREACH 1
#define UIP_CONF_DHCP_LIGHT
#ifndef UIP_CONF_RECEIVE_WINDOW
#define UIP_CONF_RECEIVE_WINDOW 48
#endif
#define UIP_CONF_TCP_MSS 48
#define UIP_CONF_UDP_CONNS 12
#define UIP_CONF_FWCACHE_SIZE 30

View file

@ -109,7 +109,7 @@
/* ND and Routing */
#define UIP_CONF_ROUTER 0 /**< BLE master role, which allows for routing, isn't supported. */
#define UIP_CONF_ND6_SEND_NA 1
#define UIP_CONF_ND6_SEND_NS 1
#define UIP_CONF_IP_FORWARD 0 /**< No packet forwarding. */
#define UIP_CONF_ND6_REACHABLE_TIME 600000

View file

@ -125,7 +125,7 @@
/** BUTTON_USER -> PC3 */
#define BUTTON_USER_PORT GPIO_C_NUM
#define BUTTON_USER_PIN 3
#define BUTTON_USER_VECTOR NVIC_INT_GPIO_PORT_C
#define BUTTON_USER_VECTOR GPIO_C_IRQn
/* Notify various examples that we have Buttons */
#define PLATFORM_HAS_BUTTON 1
/** @} */

View file

@ -416,6 +416,10 @@ typedef uint32_t rtimer_clock_t;
#define IEEE802154_CONF_PANID 0xABCD
#endif
#ifdef RF_CHANNEL
#define CC2538_RF_CONF_CHANNEL RF_CHANNEL
#endif
#ifndef CC2538_RF_CONF_CHANNEL
#define CC2538_RF_CONF_CHANNEL 26
#endif /* CC2538_RF_CONF_CHANNEL */
@ -472,10 +476,6 @@ typedef uint32_t rtimer_clock_t;
#define UIP_CONF_IP_FORWARD 0
#define RPL_CONF_STATS 0
#ifndef RPL_CONF_OF
#define RPL_CONF_OF rpl_mrhof
#endif
#define UIP_CONF_ND6_REACHABLE_TIME 600000
#define UIP_CONF_ND6_RETRANS_TIMER 10000

View file

@ -48,7 +48,6 @@
#include "contiki.h"
#include "dev/leds.h"
#include "dev/sys-ctrl.h"
#include "dev/scb.h"
#include "dev/nvic.h"
#include "dev/uart.h"
#include "dev/i2c.h"

View file

@ -158,10 +158,10 @@ config_user(int type, int value)
case SENSORS_ACTIVE:
if(value) {
GPIO_ENABLE_INTERRUPT(BUTTON_USER_PORT_BASE, BUTTON_USER_PIN_MASK);
nvic_interrupt_enable(BUTTON_USER_VECTOR);
NVIC_EnableIRQ(BUTTON_USER_VECTOR);
} else {
GPIO_DISABLE_INTERRUPT(BUTTON_USER_PORT_BASE, BUTTON_USER_PIN_MASK);
nvic_interrupt_disable(BUTTON_USER_VECTOR);
NVIC_DisableIRQ(BUTTON_USER_VECTOR);
}
return value;
case BUTTON_SENSOR_CONFIG_TYPE_INTERVAL:

View file

@ -157,7 +157,7 @@
#endif /* UIP_CONF_MAX_ROUTES */
#define UIP_CONF_ND6_SEND_RA 0
#define UIP_CONF_ND6_SEND_NA 0
#define UIP_CONF_ND6_SEND_NS 0
#define UIP_CONF_ND6_REACHABLE_TIME 600000
#define UIP_CONF_ND6_RETRANS_TIMER 10000

View file

@ -89,6 +89,15 @@
#define NETSTACK_CONF_FRAMER framer_802154
#endif
#ifdef RF_CHANNEL
#define RF_CORE_CONF_CHANNEL RF_CHANNEL
#endif
/* Number of Prop Mode RX buffers */
#ifndef PROP_MODE_CONF_RX_BUF_CNT
#define PROP_MODE_CONF_RX_BUF_CNT 4
#endif
/*
* Auto-configure Prop-mode radio if we are running on CC13xx, unless the
* project has specified otherwise. Depending on the final mode, determine a
@ -116,7 +125,7 @@
#define CONTIKIMAC_CONF_CCA_SLEEP_TIME (RTIMER_ARCH_SECOND / 210)
#define CONTIKIMAC_CONF_LISTEN_TIME_AFTER_PACKET_DETECTED (RTIMER_ARCH_SECOND / 20)
#define CONTIKIMAC_CONF_SEND_SW_ACK 1
#define CONTIKIMAC_CONF_AFTER_ACK_DETECTECT_WAIT_TIME (RTIMER_SECOND / 1000)
#define CONTIKIMAC_CONF_AFTER_ACK_DETECTED_WAIT_TIME (RTIMER_SECOND / 1000)
#define CONTIKIMAC_CONF_INTER_PACKET_INTERVAL (RTIMER_SECOND / 240)
#else
#define NETSTACK_CONF_RADIO ieee_mode_driver
@ -217,10 +226,6 @@
#define UIP_CONF_IP_FORWARD 0
#define RPL_CONF_STATS 0
#ifndef RPL_CONF_OF
#define RPL_CONF_OF rpl_mrhof
#endif
#define UIP_CONF_ND6_REACHABLE_TIME 600000
#define UIP_CONF_ND6_RETRANS_TIMER 10000

View file

@ -11,5 +11,5 @@ endif
MODULES += core/net \
core/net/mac core/net/mac/contikimac \
core/net/llsec \
core/net/llsec core/net/llsec/noncoresec \
dev/cc2420

View file

@ -222,7 +222,9 @@
#define UIP_CONF_DHCP_LIGHT
#define UIP_CONF_LLH_LEN 0
#ifndef UIP_CONF_RECEIVE_WINDOW
#define UIP_CONF_RECEIVE_WINDOW 48
#endif
#define UIP_CONF_TCP_MSS 48
#define UIP_CONF_MAX_CONNECTIONS 4
#define UIP_CONF_MAX_LISTENPORTS 8
@ -239,4 +241,8 @@
#define BOARD_STRING "Zolertia Z1 platform"
#ifndef AES_128_CONF
#define AES_128_CONF cc2420_aes_128_driver
#endif /* AES_128_CONF */
#endif /* CONTIKI_CONF_H */

View file

@ -318,10 +318,11 @@ main(int argc, char **argv)
NETSTACK_RDC.init();
NETSTACK_MAC.init();
NETSTACK_LLSEC.init();
NETSTACK_NETWORK.init();
printf("%s %s, channel check rate %lu Hz, radio channel %u\n",
NETSTACK_MAC.name, NETSTACK_RDC.name,
printf("%s %s %s, channel check rate %lu Hz, radio channel %u\n",
NETSTACK_LLSEC.name, NETSTACK_MAC.name, NETSTACK_RDC.name,
CLOCK_SECOND / (NETSTACK_RDC.channel_check_interval() == 0 ? 1 :
NETSTACK_RDC.channel_check_interval()),
CC2420_CONF_CHANNEL);
@ -359,10 +360,11 @@ main(int argc, char **argv)
NETSTACK_RDC.init();
NETSTACK_MAC.init();
NETSTACK_LLSEC.init();
NETSTACK_NETWORK.init();
printf("%s %s, channel check rate %lu Hz, radio channel %u\n",
NETSTACK_MAC.name, NETSTACK_RDC.name,
printf("%s %s %s, channel check rate %lu Hz, radio channel %u\n",
NETSTACK_LLSEC.name, NETSTACK_MAC.name, NETSTACK_RDC.name,
CLOCK_SECOND / (NETSTACK_RDC.channel_check_interval() == 0 ? 1 :
NETSTACK_RDC.channel_check_interval()),
CC2420_CONF_CHANNEL);

View file

@ -18,6 +18,11 @@ endif
PYTHON = python
BSL_FLAGS += -e -w -v
BSL_SPEED ?= 460800
# Works in Linux and probably on OSX too (RTCC example)
CFLAGS += -DDATE="\"`date +"%02u %02d %02m %02y %02H %02M %02S"`\""
### Configure the build for the board and pull in board-specific sources
CONTIKI_TARGET_DIRS += . dev
CONTIKI_TARGET_DIRS += . $(BOARD)
@ -45,10 +50,14 @@ endif
CONTIKI_CPU=$(CONTIKI)/cpu/cc2538
include $(CONTIKI_CPU)/Makefile.cc2538
MODULES += core/net core/net/mac \
MODULES += core/net core/net/mac core/net/ip \
core/net/mac/contikimac \
core/net/llsec core/net/llsec/noncoresec dev/cc1200
ifeq ($(WITH_IP64),1)
MODULES += core/net/ip64
endif
BSL = $(CONTIKI)/tools/cc2538-bsl/cc2538-bsl.py
### Use the specific Zoul subplatform to query for connected devices
@ -95,7 +104,7 @@ define UPLOAD_RULE
@BSL_ADDRESS=`$(OBJDUMP) -h $$*.elf | grep -B1 LOAD | \
grep -Ev 'LOAD|\-\-' | awk '{print "0x" $$$$5}' | \
sort -g | head -1`; \
$(PYTHON) $(BSL) $(BSL_FLAGS) -a $$$${BSL_ADDRESS} -p $(MOTE) $$<
$(PYTHON) $(BSL) $(BSL_FLAGS) -b $(BSL_SPEED) -a $$$${BSL_ADDRESS} -p $(MOTE) $$<
endef
### Create an upload rule for every MOTE connected

View file

@ -60,6 +60,7 @@ In terms of hardware support, the following drivers have been implemented for th
* Built-in core temperature and battery sensor.
* CC1200 sub-1GHz radio interface.
* Real Time Clock Calendar (on the RE-Mote platform).
* SD
There is a Zoul powering the RE-Mote and Firefly platforms, check out its specific README files for more information about on-board features.
@ -76,7 +77,11 @@ Install a Toolchain
-------------------
The toolchain used to build contiki is arm-gcc, also used by other arm-based Contiki ports. If you are using Instant Contiki, you may have a version pre-installed in your system.
The platform is currently being used/tested with "GNU Tools for ARM Embedded Processors" (<https://launchpad.net/gcc-arm-embedded>). The current recommended version and the one being used by Contiki's regression tests on Travis is shown below.
The platform is currently being used/tested with "GNU Tools for ARM Embedded Processors" (<https://launchpad.net/gcc-arm-embedded>).
Always check which version [Travis currently uses for the ARM regression testing](https://github.com/contiki-os/contiki/blob/master/.travis.yml#L54)
To find out which version your system has:
$ arm-none-eabi-gcc --version
arm-none-eabi-gcc (GNU Tools for ARM Embedded Processors) 5.2.1 20151202 (release) [ARM/embedded-5-branch revision 231848]
@ -261,7 +266,7 @@ More Reading
Maintainers
===========
The Zoul and derived platforms (as well as the Z1 mote) are maintained by Zolertia.
Main contributor: Antonio Lignan <alignan@zolertia.com>
Main contributor: Antonio Lignan <alinan@zolertia.com> <antonio.lignan@gmail.com>
[zolertia-site]: http://www.zolertia.io/products "Zolertia"
[zolertia-wiki]: https://github.com/Zolertia/Resources/wiki "Zolertia Wiki"

View file

@ -322,8 +322,8 @@ typedef uint32_t rtimer_clock_t;
#endif
/* Configure NullRDC for when it's selected */
#define NULLRDC_802154_AUTOACK 1
#define NULLRDC_802154_AUTOACK_HW 1
#define NULLRDC_CONF_802154_AUTOACK 1
#define NULLRDC_CONF_802154_AUTOACK_HW 1
/* Configure ContikiMAC for when it's selected */
#define CONTIKIMAC_CONF_WITH_PHASE_OPTIMIZATION 0
@ -341,6 +341,26 @@ typedef uint32_t rtimer_clock_t;
#endif /* NETSTACK_CONF_WITH_IPV6 */
#endif /* NETSTACK_CONF_FRAMER */
#if CC1200_CONF_SUBGHZ_50KBPS_MODE
#define NETSTACK_CONF_RADIO cc1200_driver
#define CC1200_CONF_RF_CFG cc1200_802154g_863_870_fsk_50kbps
#define ANTENNA_SW_SELECT_DEF_CONF ANTENNA_SW_SELECT_SUBGHZ
#define CC1200_CONF_USE_GPIO2 0
#define CC1200_CONF_USE_RX_WATCHDOG 0
#define NULLRDC_CONF_ACK_WAIT_TIME (RTIMER_SECOND / 200)
#define NULLRDC_CONF_AFTER_ACK_DETECTED_WAIT_TIME (RTIMER_SECOND / 1500)
#define NULLRDC_CONF_802154_AUTOACK 1
#define NULLRDC_CONF_802154_AUTOACK_HW 1
#define NULLRDC_CONF_SEND_802154_ACK 0
#define CONTIKIMAC_CONF_CCA_CHECK_TIME (RTIMER_ARCH_SECOND / 800)
#define CONTIKIMAC_CONF_CCA_SLEEP_TIME (RTIMER_ARCH_SECOND / 120)
#define CONTIKIMAC_CONF_LISTEN_TIME_AFTER_PACKET_DETECTED (RTIMER_ARCH_SECOND / 8)
#define CONTIKIMAC_CONF_AFTER_ACK_DETECTED_WAIT_TIME (RTIMER_SECOND / 300)
#define CONTIKIMAC_CONF_INTER_PACKET_INTERVAL (RTIMER_SECOND / 200)
#endif
/* This can be overriden to use the cc1200_driver instead */
#ifndef NETSTACK_CONF_RADIO
#define NETSTACK_CONF_RADIO cc2538_rf_driver
@ -433,6 +453,10 @@ typedef uint32_t rtimer_clock_t;
#define IEEE802154_CONF_PANID 0xABCD
#endif
#ifdef RF_CHANNEL
#define CC2538_RF_CONF_CHANNEL RF_CHANNEL
#endif
#ifndef CC2538_RF_CONF_CHANNEL
#define CC2538_RF_CONF_CHANNEL 26
#endif /* CC2538_RF_CONF_CHANNEL */
@ -489,10 +513,6 @@ typedef uint32_t rtimer_clock_t;
#define UIP_CONF_IP_FORWARD 0
#define RPL_CONF_STATS 0
#ifndef RPL_CONF_OF
#define RPL_CONF_OF rpl_mrhof
#endif
#define UIP_CONF_ND6_REACHABLE_TIME 600000
#define UIP_CONF_ND6_RETRANS_TIMER 10000
@ -573,6 +593,27 @@ typedef uint32_t rtimer_clock_t;
#endif
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name RTC
*
* @{
*/
#ifdef PLATFORM_HAS_RTC
#ifndef RTC_CONF_INIT
#define RTC_CONF_INIT 0 /**< Whether to initialize the RTC */
#endif
#ifndef RTC_CONF_SET_FROM_SYS
#define RTC_CONF_SET_FROM_SYS 0 /**< Whether to set the RTC from the build system */
#endif
#else
#undef RTC_CONF_INIT
#define RTC_CONF_INIT 0
#endif
/** @} */
/*---------------------------------------------------------------------------*/
#endif /* CONTIKI_CONF_H_ */

View file

@ -47,7 +47,6 @@
#include "contiki.h"
#include "dev/leds.h"
#include "dev/sys-ctrl.h"
#include "dev/scb.h"
#include "dev/nvic.h"
#include "dev/uart.h"
#include "dev/watchdog.h"
@ -58,6 +57,7 @@
#include "dev/cc2538-rf.h"
#include "dev/udma.h"
#include "dev/crypto.h"
#include "dev/rtcc.h"
#include "usb/usb-serial.h"
#include "lib/random.h"
#include "net/netstack.h"
@ -73,6 +73,7 @@
#include <stdint.h>
#include <string.h>
#include <stdlib.h>
#include <stdio.h>
/*---------------------------------------------------------------------------*/
#if STARTUP_CONF_VERBOSE
@ -110,6 +111,62 @@ fade(unsigned char l)
}
/*---------------------------------------------------------------------------*/
static void
rtc_init(void)
{
#if RTC_CONF_INIT
#if RTC_CONF_SET_FROM_SYS
char *next;
simple_td_map td;
#endif
/* Configure RTC and return structure with all parameters */
rtcc_init();
#if RTC_CONF_SET_FROM_SYS
#ifndef DATE
#error Could not retrieve date from system
#endif
/* Alternatively, for test only, undefine DATE and define it on your own as:
* #define DATE "07 06 12 15 16 00 00"
* Also note that if you restart the node at a given time, it will use the
* already defined DATE, so if you want to update the device date/time you
* need to reflash the node.
*/
/* Get the system date in the following format: wd dd mm yy hh mm ss */
PRINTF("Setting RTC from system date: %s\n", DATE);
/* Configure the RTC with the current values */
td.weekdays = (uint8_t)strtol(DATE, &next, 10);
td.day = (uint8_t)strtol(next, &next, 10);
td.months = (uint8_t)strtol(next, &next, 10);
td.years = (uint8_t)strtol(next, &next, 10);
td.hours = (uint8_t)strtol(next, &next, 10);
td.minutes = (uint8_t)strtol(next, &next, 10);
td.seconds = (uint8_t)strtol(next, NULL, 10);
/* Don't care about the milliseconds... */
td.miliseconds = 0;
/* This example relies on 24h mode */
td.mode = RTCC_24H_MODE;
/*
* And to simplify the configuration, it relies on the fact that it will be
* executed in the present century
*/
td.century = RTCC_CENTURY_20XX;
/* Set the time and date */
if(rtcc_set_time_date(&td) == AB08_ERROR) {
PRINTF("Failed to set time and date\n");
}
#endif
#endif
}
/*---------------------------------------------------------------------------*/
static void
set_rf_params(void)
{
uint16_t short_addr;
@ -205,6 +262,8 @@ main(void)
crypto_disable();
#endif
rtc_init();
netstack_init();
set_rf_params();

View file

@ -137,7 +137,7 @@ configure(int type, int value)
/* Enable interrupts */
GPIO_ENABLE_INTERRUPT(DIMMER_SYNC_PORT_BASE, DIMMER_SYNC_PIN_MASK);
// ioc_set_over(DIMMER_SYNC_PORT, DIMMER_SYNC_PIN, IOC_OVERRIDE_PUE);
nvic_interrupt_enable(DIMMER_INT_VECTOR);
NVIC_EnableIRQ(DIMMER_INT_VECTOR);
enabled = 1;
dimming = DIMMER_DEFAULT_START_VALUE;

View file

@ -73,7 +73,7 @@
#ifdef DIMMER_CONF_INT_VECTOR
#define DIMMER_INT_VECTOR DIMMER_CONF_INT_VECTOR
#else
#define DIMMER_INT_VECTOR NVIC_INT_GPIO_PORT_A
#define DIMMER_INT_VECTOR GPIO_A_IRQn
#endif
/** @} */
/* -------------------------------------------------------------------------- */

View file

@ -162,7 +162,8 @@ configure(int type, int value)
}
adc_init();
set_decimation_rate(SOC_ADC_ADCCON_DIV_512);
enabled_channels += value;
enabled_channels |= value;
PRINTF("ADC: enabled channels 0x%02X\n", enabled_channels);
break;
case ZOUL_SENSORS_CONFIGURE_TYPE_DECIMATION_RATE:

View file

@ -0,0 +1,78 @@
/*
* Copyright (c) 2015, Zolertia
* 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.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup zoul-bme280-sensor
* @{
*
* \file
* Architecture-specific I2C for the external BME280 weather sensor
*
* \author
* Antonio Lignan <alinan@zolertia.com>
*/
/*---------------------------------------------------------------------------*/
#include "contiki.h"
#include "dev/i2c.h"
/*---------------------------------------------------------------------------*/
void
bme280_arch_i2c_init(void)
{
i2c_init(I2C_SDA_PORT, I2C_SDA_PIN, I2C_SCL_PORT, I2C_SCL_PIN,
I2C_SCL_NORMAL_BUS_SPEED);
}
/*---------------------------------------------------------------------------*/
void
bme280_arch_i2c_write_mem(uint8_t addr, uint8_t reg, uint8_t value)
{
uint8_t buf[2];
buf[0] = reg;
buf[1] = value;
i2c_master_enable();
i2c_burst_send(addr, buf, 2);
}
/*---------------------------------------------------------------------------*/
void
bme280_arch_i2c_read_mem(uint8_t addr, uint8_t reg, uint8_t *buf, uint8_t bytes)
{
i2c_master_enable();
if(i2c_single_send(addr, reg) == I2C_MASTER_ERR_NONE) {
while(i2c_master_busy());
i2c_burst_receive(addr, buf, bytes);
}
}
/*---------------------------------------------------------------------------*/
/**
* @}
*/

View file

@ -157,10 +157,10 @@ config_user(int type, int value)
case SENSORS_ACTIVE:
if(value) {
GPIO_ENABLE_INTERRUPT(BUTTON_USER_PORT_BASE, BUTTON_USER_PIN_MASK);
nvic_interrupt_enable(BUTTON_USER_VECTOR);
NVIC_EnableIRQ(BUTTON_USER_VECTOR);
} else {
GPIO_DISABLE_INTERRUPT(BUTTON_USER_PORT_BASE, BUTTON_USER_PIN_MASK);
nvic_interrupt_disable(BUTTON_USER_VECTOR);
NVIC_DisableIRQ(BUTTON_USER_VECTOR);
}
return value;
case BUTTON_SENSOR_CONFIG_TYPE_INTERVAL:

View file

@ -183,7 +183,7 @@ cc1200_arch_gpio0_setup_irq(int rising)
GPIO_ENABLE_INTERRUPT(CC1200_GDO0_PORT_BASE, CC1200_GDO0_PIN_MASK);
ioc_set_over(CC1200_GDO0_PORT, CC1200_GDO0_PIN, IOC_OVERRIDE_PUE);
nvic_interrupt_enable(CC1200_GPIOx_VECTOR);
NVIC_EnableIRQ(CC1200_GPIOx_VECTOR);
gpio_register_callback(cc1200_int_handler, CC1200_GDO0_PORT,
CC1200_GDO0_PIN);
}
@ -205,7 +205,7 @@ cc1200_arch_gpio2_setup_irq(int rising)
GPIO_ENABLE_INTERRUPT(CC1200_GDO2_PORT_BASE, CC1200_GDO2_PIN_MASK);
ioc_set_over(CC1200_GDO2_PORT, CC1200_GDO2_PIN, IOC_OVERRIDE_PUE);
nvic_interrupt_enable(CC1200_GPIOx_VECTOR);
NVIC_EnableIRQ(CC1200_GPIOx_VECTOR);
gpio_register_callback(cc1200_int_handler, CC1200_GDO2_PORT,
CC1200_GDO2_PIN);
}
@ -215,7 +215,7 @@ cc1200_arch_gpio0_enable_irq(void)
{
GPIO_ENABLE_INTERRUPT(CC1200_GDO0_PORT_BASE, CC1200_GDO0_PIN_MASK);
ioc_set_over(CC1200_GDO0_PORT, CC1200_GDO0_PIN, IOC_OVERRIDE_PUE);
nvic_interrupt_enable(CC1200_GPIOx_VECTOR);
NVIC_EnableIRQ(CC1200_GPIOx_VECTOR);
}
/*---------------------------------------------------------------------------*/
void
@ -229,7 +229,7 @@ cc1200_arch_gpio2_enable_irq(void)
{
GPIO_ENABLE_INTERRUPT(CC1200_GDO2_PORT_BASE, CC1200_GDO2_PIN_MASK);
ioc_set_over(CC1200_GDO2_PORT, CC1200_GDO2_PIN, IOC_OVERRIDE_PUE);
nvic_interrupt_enable(CC1200_GPIOx_VECTOR);
NVIC_EnableIRQ(CC1200_GPIOx_VECTOR);
}
/*---------------------------------------------------------------------------*/
void
@ -241,7 +241,7 @@ cc1200_arch_gpio2_disable_irq(void)
int
cc1200_arch_gpio0_read_pin(void)
{
return GPIO_READ_PIN(CC1200_GDO0_PORT_BASE, CC1200_GDO0_PIN_MASK);
return (GPIO_READ_PIN(CC1200_GDO0_PORT_BASE, CC1200_GDO0_PIN_MASK) ? 1 : 0);
}
/*---------------------------------------------------------------------------*/
int

View file

@ -603,7 +603,7 @@ configure(int type, int value)
int_en = 1;
GPIO_ENABLE_INTERRUPT(GROVE_GYRO_INT_PORT_BASE, GROVE_GYRO_INT_PIN_MASK);
ioc_set_over(I2C_INT_PORT, I2C_INT_PIN, IOC_OVERRIDE_PUE);
nvic_interrupt_enable(I2C_INT_VECTOR);
NVIC_EnableIRQ(I2C_INT_VECTOR);
PRINTF("Gyro: Data interrupt configured\n");
return GROVE_GYRO_SUCCESS;

View file

@ -0,0 +1,139 @@
/*
* Copyright (c) 2016, Benoît Thébaudeau <benoit@wsystem.com>
* 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.
*/
/**
* \addtogroup mmc-arch
* @{
*
* \file
* Implementation of the SD/MMC device driver RE-Mote-specific definitions.
*/
#include <stddef.h>
#include <stdbool.h>
#include <stdint.h>
#include "spi-arch.h"
#include "dev/ioc.h"
#include "dev/gpio.h"
#include "dev/spi.h"
#include "mmc-arch.h"
#define USD_SEL_PORT_BASE GPIO_PORT_TO_BASE(USD_SEL_PORT)
#define USD_SEL_PIN_MASK GPIO_PIN_MASK(USD_SEL_PIN)
/*----------------------------------------------------------------------------*/
static void
mmc_arch_init(void)
{
static uint8_t init_done;
if(init_done) {
return;
}
GPIO_SET_INPUT(USD_SEL_PORT_BASE, USD_SEL_PIN_MASK);
GPIO_SOFTWARE_CONTROL(USD_SEL_PORT_BASE, USD_SEL_PIN_MASK);
ioc_set_over(USD_SEL_PORT, USD_SEL_PIN, IOC_OVERRIDE_DIS);
spix_cs_init(USD_CSN_PORT, USD_CSN_PIN);
spix_init(USD_SPI_INSTANCE);
spix_set_mode(USD_SPI_INSTANCE, SSI_CR0_FRF_MOTOROLA, 0, 0, 8);
init_done = 1;
}
/*----------------------------------------------------------------------------*/
bool
mmc_arch_get_cd(uint8_t dev)
{
mmc_arch_init();
if(GPIO_IS_OUTPUT(USD_SEL_PORT_BASE, USD_SEL_PIN_MASK)) {
/* Card previously detected and powered */
return true;
} else if(GPIO_READ_PIN(USD_SEL_PORT_BASE, USD_SEL_PIN_MASK)) {
/* Card inserted -> power it */
GPIO_SET_OUTPUT(USD_SEL_PORT_BASE, USD_SEL_PIN_MASK);
GPIO_CLR_PIN(USD_SEL_PORT_BASE, USD_SEL_PIN_MASK);
return true;
} else {
/* No card detected */
return false;
}
}
/*----------------------------------------------------------------------------*/
bool
mmc_arch_get_wp(uint8_t dev)
{
return false;
}
/*----------------------------------------------------------------------------*/
void
mmc_arch_spi_select(uint8_t dev, bool sel)
{
if(sel) {
SPIX_CS_CLR(USD_CSN_PORT, USD_CSN_PIN);
} else {
SPIX_CS_SET(USD_CSN_PORT, USD_CSN_PIN);
}
}
/*----------------------------------------------------------------------------*/
void
mmc_arch_spi_set_clock_freq(uint8_t dev, uint32_t freq)
{
spix_set_clock_freq(USD_SPI_INSTANCE, freq);
}
/*----------------------------------------------------------------------------*/
void
mmc_arch_spi_xfer(uint8_t dev, const void *tx_buf, size_t tx_cnt,
void *rx_buf, size_t rx_cnt)
{
const uint8_t *tx_buf_u8 = tx_buf;
uint8_t *rx_buf_u8 = rx_buf;
while(tx_cnt || rx_cnt) {
SPIX_WAITFORTxREADY(USD_SPI_INSTANCE);
if(tx_cnt) {
SPIX_BUF(USD_SPI_INSTANCE) = *tx_buf_u8++;
tx_cnt--;
} else {
SPIX_BUF(USD_SPI_INSTANCE) = 0;
}
SPIX_WAITFOREOTx(USD_SPI_INSTANCE);
SPIX_WAITFOREORx(USD_SPI_INSTANCE);
if(rx_cnt) {
*rx_buf_u8++ = SPIX_BUF(USD_SPI_INSTANCE);
rx_cnt--;
} else {
SPIX_BUF(USD_SPI_INSTANCE);
}
}
}
/*----------------------------------------------------------------------------*/
/** @} */

View file

@ -119,7 +119,7 @@ configure(int type, int value)
process_start(&motion_int_process, NULL);
GPIO_ENABLE_INTERRUPT(MOTION_SENSOR_PORT_BASE, MOTION_SENSOR_PIN_MASK);
nvic_interrupt_enable(MOTION_SENSOR_VECTOR);
NVIC_EnableIRQ(MOTION_SENSOR_VECTOR);
return MOTION_SUCCESS;
}
/*---------------------------------------------------------------------------*/

View file

@ -523,7 +523,7 @@ rtcc_set_alarm_time_date(simple_td_map *data, uint8_t state, uint8_t repeat,
} else {
GPIO_ENABLE_INTERRUPT(RTC_INT1_PORT_BASE, RTC_INT1_PIN_MASK);
ioc_set_over(RTC_INT1_PORT, RTC_INT1_PIN, IOC_OVERRIDE_PUE);
nvic_interrupt_enable(RTC_INT1_VECTOR);
NVIC_EnableIRQ(RTC_INT1_VECTOR);
}
if (trigger == RTCC_TRIGGER_INT1) {

View file

@ -453,7 +453,7 @@ configure(int type, int value)
* resistor instead if no external pull-up is present.
*/
ioc_set_over(I2C_INT_PORT, I2C_INT_PIN, IOC_OVERRIDE_PUE);
nvic_interrupt_enable(I2C_INT_VECTOR);
NVIC_EnableIRQ(I2C_INT_VECTOR);
PRINTF("TSL256X: Interrupt configured\n");
return TSL256X_SUCCESS;

View file

@ -449,8 +449,8 @@ configure(int type, int value)
GPIO_ENABLE_INTERRUPT(ANEMOMETER_SENSOR_PORT_BASE, ANEMOMETER_SENSOR_PIN_MASK);
GPIO_ENABLE_INTERRUPT(RAIN_GAUGE_SENSOR_PORT_BASE, RAIN_GAUGE_SENSOR_PIN_MASK);
nvic_interrupt_enable(ANEMOMETER_SENSOR_VECTOR);
nvic_interrupt_enable(RAIN_GAUGE_SENSOR_VECTOR);
NVIC_EnableIRQ(ANEMOMETER_SENSOR_VECTOR);
NVIC_EnableIRQ(RAIN_GAUGE_SENSOR_VECTOR);
enabled = 1;
PRINTF("Weather: started\n");

View file

@ -118,7 +118,7 @@ extern void (*rain_gauge_int_callback)(uint16_t value);
#ifdef WEATHER_METER_CONF_ANEMOMETER_VECTOR
#define ANEMOMETER_SENSOR_VECTOR WEATHER_METER_CONF_ANEMOMETER_VECTOR
#else
#define ANEMOMETER_SENSOR_VECTOR NVIC_INT_GPIO_PORT_D
#define ANEMOMETER_SENSOR_VECTOR GPIO_D_IRQn
#endif
/** @} */
/* -------------------------------------------------------------------------- */
@ -139,7 +139,7 @@ extern void (*rain_gauge_int_callback)(uint16_t value);
#ifdef WEATHER_METER_CONF_RAIN_GAUGE_VECTOR
#define RAIN_GAUGE_SENSOR_VECTOR WEATHER_METER_CONF_RAIN_GAUGE_VECTOR
#else
#define RAIN_GAUGE_SENSOR_VECTOR NVIC_INT_GPIO_PORT_D
#define RAIN_GAUGE_SENSOR_VECTOR GPIO_D_IRQn
#endif
/** @} */
/* -------------------------------------------------------------------------- */

View file

@ -37,5 +37,5 @@ Firefly pin-out
![Firefly Revision A pin-out (front)][firefly-reva-pinout-front]
[firefly-reva-pinout-front]: ../images/firefly-pinout-front.png "Firefly Revision A pin-out (front)"
[firefly-reva]: ../images/firefly-reva.png "Zolertia Firefly Revision A breakout board"
[firefly-reva-pinout-front]: ../images/firefly-reva-pinout-front.png "Firefly Revision A pin-out (front)"
[firefly-reva]: ../images/firefly-reva.jpg "Zolertia Firefly Revision A breakout board"

View file

@ -265,7 +265,7 @@
/** BUTTON_USER -> PA3 */
#define BUTTON_USER_PORT GPIO_A_NUM
#define BUTTON_USER_PIN 3
#define BUTTON_USER_VECTOR NVIC_INT_GPIO_PORT_A
#define BUTTON_USER_VECTOR GPIO_A_IRQn
/* Notify various examples that we have an user button.
* If ADC6 channel is used, then disable the user button
@ -330,7 +330,7 @@
#define I2C_SDA_PIN 2
#define I2C_INT_PORT GPIO_D_NUM
#define I2C_INT_PIN 1
#define I2C_INT_VECTOR NVIC_INT_GPIO_PORT_D
#define I2C_INT_VECTOR GPIO_D_IRQn
/** @} */
/*---------------------------------------------------------------------------*/
/**
@ -368,7 +368,7 @@
#define CC1200_GDO2_PIN 0
#define CC1200_RESET_PORT GPIO_C_NUM
#define CC1200_RESET_PIN 7
#define CC1200_GPIOx_VECTOR NVIC_INT_GPIO_PORT_B
#define CC1200_GPIOx_VECTOR GPIO_B_IRQn
/** @} */
/*---------------------------------------------------------------------------*/
/**

View file

@ -264,7 +264,7 @@
/** BUTTON_USER -> PA3 */
#define BUTTON_USER_PORT GPIO_A_NUM
#define BUTTON_USER_PIN 3
#define BUTTON_USER_VECTOR NVIC_INT_GPIO_PORT_A
#define BUTTON_USER_VECTOR GPIO_A_IRQn
/* Notify various examples that we have an user button.
* If ADC6 channel is used, then disable the user button
@ -329,7 +329,7 @@
#define I2C_SDA_PIN 2
#define I2C_INT_PORT GPIO_D_NUM
#define I2C_INT_PIN 1
#define I2C_INT_VECTOR NVIC_INT_GPIO_PORT_D
#define I2C_INT_VECTOR GPIO_D_IRQn
/** @} */
/*---------------------------------------------------------------------------*/
/**
@ -367,7 +367,7 @@
#define CC1200_GDO2_PIN 0
#define CC1200_RESET_PORT GPIO_C_NUM
#define CC1200_RESET_PIN 7
#define CC1200_GPIOx_VECTOR NVIC_INT_GPIO_PORT_B
#define CC1200_GPIOx_VECTOR GPIO_B_IRQn
/** @} */
/*---------------------------------------------------------------------------*/
/**

View file

@ -0,0 +1,84 @@
/*
* Copyright (c) 2016, Benoît Thébaudeau <benoit@wsystem.com>
* 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.
*/
/**
* \addtogroup remote-fat
* @{
*
* \file
* Implementation of the default port of FatFs on RE-Mote.
*/
#include "diskio.h"
#include "mmc.h"
#include "rtcc.h"
/*----------------------------------------------------------------------------*/
DSTATUS __attribute__((__weak__))
disk_status(BYTE pdrv)
{
return ~mmc_driver.status(pdrv);
}
/*----------------------------------------------------------------------------*/
DSTATUS __attribute__((__weak__))
disk_initialize(BYTE pdrv)
{
return ~mmc_driver.initialize(pdrv);
}
/*----------------------------------------------------------------------------*/
DRESULT __attribute__((__weak__))
disk_read(BYTE pdrv, BYTE *buff, DWORD sector, UINT count)
{
return mmc_driver.read(pdrv, buff, sector, count);
}
/*----------------------------------------------------------------------------*/
DRESULT __attribute__((__weak__))
disk_write(BYTE pdrv, const BYTE *buff, DWORD sector, UINT count)
{
return mmc_driver.write(pdrv, buff, sector, count);
}
/*----------------------------------------------------------------------------*/
DRESULT __attribute__((__weak__))
disk_ioctl(BYTE pdrv, BYTE cmd, void *buff)
{
return mmc_driver.ioctl(pdrv, cmd, buff);
}
/*----------------------------------------------------------------------------*/
DWORD __attribute__((__weak__))
get_fattime(void)
{
simple_td_map td;
return rtcc_get_time_date(&td) == AB08_SUCCESS ?
(2000 + td.years - 1980) << 25 | td.months << 21 | td.day << 16 |
td.hours << 11 | td.minutes << 5 | td.seconds : 0;
}
/*----------------------------------------------------------------------------*/
/** @} */

View file

@ -0,0 +1,418 @@
/*
* Copyright (c) 2016, Benoît Thébaudeau <benoit@wsystem.com>
* All rights reserved.
*
* Based on the FatFs Module,
* Copyright (c) 2016, ChaN
* 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.
*/
/**
* \addtogroup remote
* @{
*
* \defgroup remote-fat RE-Mote FatFs
*
* Default port of FatFs on RE-Mote.
* @{
*
* \file
* Header file configuring FatFs for RE-Mote.
*/
#ifndef FFCONF_H_
#define FFCONF_H_
#include "contiki-conf.h"
#define _FFCONF 68020 /**< Revision ID */
/*----------------------------------------------------------------------------*/
/** \name Function Configuration
* @{
*/
#ifndef _FS_READONLY
/** This option switches the read-only configuration
* (\c 0: read/write or \c 1: read-only).
*
* The read-only configuration removes the writing functions from the API:
* \c f_write(), \c f_sync(), \c f_unlink(), \c f_mkdir(), \c f_chmod(),
* \c f_rename(), \c f_truncate(), \c f_getfree(), and optional writing
* functions as well.
*/
#define _FS_READONLY 0
#endif
#ifndef _FS_MINIMIZE
/** This option defines the minimization level to remove some basic API
* functions.
*
* \c 0: All the basic functions are enabled.
* \c 1: \c f_stat(), \c f_getfree(), \c f_unlink(), \c f_mkdir(),
* \c f_truncate(), and \c f_rename() are removed.
* \c 2: \c f_opendir(), \c f_readdir(), and \c f_closedir() are removed in
* addition to \c 1.
* \c 3: \c f_lseek() is removed in addition to \c 2.
*/
#define _FS_MINIMIZE 0
#endif
#ifndef _USE_STRFUNC
/** This option switches the string functions: \c f_gets(), \c f_putc(),
* \c f_puts(), and \c f_printf().
*
* \c 0: Disable string functions.
* \c 1: Enable without LF-CRLF conversion.
* \c 2: Enable with LF-CRLF conversion.
*/
#define _USE_STRFUNC 1
#endif
#ifndef _USE_FIND
/** This option switches the filtered directory read functions: \c f_findfirst()
* and \c f_findnext() (\c 0: disable, \c 1: enable, \c 2: enable with matching
* \c altname[] too).
*/
#define _USE_FIND 1
#endif
#ifndef _USE_MKFS
/** This option switches the \c f_mkfs() function
* (\c 0: disable or \c 1: enable).
*/
#define _USE_MKFS 1
#endif
#ifndef _USE_FASTSEEK
/** This option switches the fast seek function
* (\c 0: disable or \c 1: enable).
*/
#define _USE_FASTSEEK 0
#endif
#ifndef _USE_EXPAND
/** This option switches the \c f_expand() function
* (\c 0: disable or \c 1: enable).
*/
#define _USE_EXPAND 0
#endif
#ifndef _USE_CHMOD
/** This option switches the attribute manipulation functions: \c f_chmod() and
* \c f_utime() (\c 0: disable or \c 1: enable). Also, \c _FS_READONLY needs to
* be \c 0 to enable this option.
*/
#define _USE_CHMOD 1
#endif
#ifndef _USE_LABEL
/** This option switches the volume label functions: \c f_getlabel() and
* \c f_setlabel() (\c 0: disable or \c 1: enable).
*/
#define _USE_LABEL 1
#endif
#ifndef _USE_FORWARD
/** This option switches the \c f_forward() function
* (\c 0: disable or \c 1: enable).
*/
#define _USE_FORWARD 0
#endif
/** @} */
/*----------------------------------------------------------------------------*/
/** \name Locale and Namespace Configuration
* @{
*/
#ifndef _CODE_PAGE
/** This option specifies the OEM code page to be used on the target system.
* Incorrect setting of the code page can cause a file open failure.
*
* \c 1 - ASCII (no extended character, non-LFN cfg. only)
* \c 437 - U.S.
* \c 720 - Arabic
* \c 737 - Greek
* \c 771 - KBL
* \c 775 - Baltic
* \c 850 - Latin 1
* \c 852 - Latin 2
* \c 855 - Cyrillic
* \c 857 - Turkish
* \c 860 - Portuguese
* \c 861 - Icelandic
* \c 862 - Hebrew
* \c 863 - Canadian French
* \c 864 - Arabic
* \c 865 - Nordic
* \c 866 - Russian
* \c 869 - Greek 2
* \c 932 - Japanese (DBCS)
* \c 936 - Simplified Chinese (DBCS)
* \c 949 - Korean (DBCS)
* \c 950 - Traditional Chinese (DBCS)
*/
#define _CODE_PAGE 437
#endif
#ifndef _USE_LFN
/** \c _USE_LFN switches the support of long file name (LFN).
*
* \c 0: Disable LFN support. \c _MAX_LFN has no effect.
* \c 1: Enable LFN with static working buffer on the BSS. Always thread-unsafe.
* \c 2: Enable LFN with dynamic working buffer on the STACK.
* \c 3: Enable LFN with dynamic working buffer on the HEAP.
*
* To enable LFN, the Unicode handling functions (<tt>option/unicode.c</tt>)
* must be added to the project. The working buffer occupies
* <tt>(_MAX_LFN + 1) * 2</tt> bytes, and 608 more bytes with exFAT enabled.
* \c _MAX_LFN can be in the range from 12 to 255. It should be set to 255 to
* support the full-featured LFN operations. When using the stack for the
* working buffer, take care of stack overflow. When using the heap memory for
* the working buffer, the memory management functions, \c ff_memalloc() and
* \c ff_memfree(), must be added to the project.
*/
#define _USE_LFN 3
#endif
#ifndef _MAX_LFN
#define _MAX_LFN 255
#endif
#ifndef _LFN_UNICODE
/** This option switches the character encoding in the API
* (\c 0: ANSI/OEM or \c 1: UTF-16).
*
* To use a Unicode string for the path name, enable LFN and set \c _LFN_UNICODE
* to \c 1.
* This option also affects the behavior of the string I/O functions.
*/
#define _LFN_UNICODE 0
#endif
#ifndef _STRF_ENCODE
/** If \c _LFN_UNICODE is set to \c 1, this option selects the character
* encoding OF THE FILE to be read/written via the string I/O functions:
* \c f_gets(), \c f_putc(), \c f_puts(), and \c f_printf().
*
* \c 0: ANSI/OEM
* \c 1: UTF-16LE
* \c 2: UTF-16BE
* \c 3: UTF-8
*
* This option has no effect if \c _LFN_UNICODE is set to \c 0.
*/
#define _STRF_ENCODE 0
#endif
#ifndef _FS_RPATH
/** This option configures the support of relative path.
*
* \c 0: Disable relative path and remove related functions.
* \c 1: Enable relative path. \c f_chdir() and \c f_chdrive() are available.
* \c 2: \c f_getcwd() is available in addition to \c 1.
*/
#define _FS_RPATH 2
#endif
/** @} */
/*----------------------------------------------------------------------------*/
/** \name Drive/Volume Configuration
* @{
*/
#ifndef _VOLUMES
/** Number of volumes (logical drives) to be used. */
#define _VOLUMES 1
#endif
#ifndef _STR_VOLUME_ID
/** \c _STR_VOLUME_ID switches the string support of volume ID.
* If \c _STR_VOLUME_ID is set to \c 1, pre-defined strings can also be used as
* drive number in the path name. \c _VOLUME_STRS defines the drive ID strings
* for each logical drive. The number of items must be equal to \c _VOLUMES.
* The valid characters for the drive ID strings are: A-Z and 0-9.
*/
#define _STR_VOLUME_ID 0
#endif
#ifndef _VOLUME_STRS
#define _VOLUME_STRS "RAM","NAND","CF","SD","SD2","USB","USB2","USB3"
#endif
#ifndef _MULTI_PARTITION
/** This option switches support of multi-partition on a physical drive.
* By default (0), each logical drive number is bound to the same physical drive
* number and only an FAT volume found on the physical drive will be mounted.
* When multi-partition is enabled (1), each logical drive number can be bound to
* arbitrary physical drive and partition listed in the VolToPart[]. Also f_fdisk()
* funciton will be available.
*/
#define _MULTI_PARTITION 0
#endif
#ifndef _MIN_SS
/** These options configure the range of sector size to be supported (512, 1024,
* 2048, or 4096). Always set both to 512 for most systems, all types of memory
* cards and harddisk. But a larger value may be required for on-board flash
* memory and some types of optical media. When \c _MAX_SS is larger than
* \c _MIN_SS, FatFs is configured to variable sector size and the
* \c GET_SECTOR_SIZE command must be implemented in \c disk_ioctl().
*/
#define _MIN_SS 512
#endif
#ifndef _MAX_SS
#define _MAX_SS 512
#endif
#ifndef _USE_TRIM
/** This option switches the support of ATA-TRIM
* (\c 0: disable or \c 1: enable).
*
* To enable the Trim function, the \c CTRL_TRIM command should also be
* implemented in \c disk_ioctl().
*/
#define _USE_TRIM 0
#endif
#ifndef _FS_NOFSINFO
/** If you need to know the correct free space on the FAT32 volume, set the bit
* 0 of this option, and the \c f_getfree() function will force a full FAT scan
* on the first time after a volume mount. The bit 1 controls the use of the
* last allocated cluster number.
*
* bit 0=0: Use the free cluster count in FSINFO if available.
* bit 0=1: Do not trust the free cluster count in FSINFO.
* bit 1=0: Use the last allocated cluster number in FSINFO if available.
* bit 1=1: Do not trust the last allocated cluster number in FSINFO.
*/
#define _FS_NOFSINFO 3
#endif
/** @} */
/*----------------------------------------------------------------------------*/
/** \name System Configuration
* @{
*/
#ifndef _FS_TINY
/** This option switches the tiny buffer configuration
* (\c 0: normal or \c 1: tiny).
*
* With the tiny configuration, the size of a file object (FIL) is reduced to
* \c _MAX_SS bytes. Instead of the private sector buffer eliminated from the
* file object, a common sector buffer in the file system object (FATFS) is used
* for the file data transfer.
*/
#define _FS_TINY 0
#endif
#ifndef _FS_EXFAT
/** This option switches the support of the exFAT file system
* (\c 0: disable or \c 1: enable).
*
* With exFAT enabled, LFN also needs to be enabled (\c _USE_LFN >= 1).
* Note that enabling exFAT discards C89 compatibility.
*/
#define _FS_EXFAT 1
#endif
#ifndef _FS_NORTC
/** The option \c _FS_NORTC switches the timestamp function. If the system does
* not have any RTC function or if a valid timestamp is not needed, set
* \c _FS_NORTC to \c 1 to disable the timestamp function. All the objects
* modified by FatFs will have a fixed timestamp defined by \c _NORTC_MON,
* \c _NORTC_MDAY, and \c _NORTC_YEAR in local time.
* To enable the timestamp function (\c _FS_NORTC set to \c 0), \c get_fattime()
* needs to be added to the project to get the current time from a real-time
* clock. \c _NORTC_MON, \c _NORTC_MDAY, and \c _NORTC_YEAR have no effect.
* These options have no effect with a read-only configuration (\c _FS_READONLY
* set to \c 1).
*/
#define _FS_NORTC (!RTC_CONF_INIT)
#endif
#ifndef _NORTC_MON
#define _NORTC_MON 1
#endif
#ifndef _NORTC_MDAY
#define _NORTC_MDAY 1
#endif
#ifndef _NORTC_YEAR
#define _NORTC_YEAR 2016
#endif
#ifndef _FS_LOCK
/** The option \c _FS_LOCK switches the file lock function controlling duplicate
* file open and illegal operations on the open objects. This option must be set
* to \c 0 if \c _FS_READONLY is \c 1.
*
* \c 0: Disable the file lock function. To avoid volume corruption, the
* application program should avoid illegal open, remove, and rename on
* the open objects.
* \c >0: Enable the file lock function. The value defines how many
* files/sub-directories can be opened simultaneously under file lock
* control. Note that the file lock control is independent of
* re-entrancy.
*/
#define _FS_LOCK 0
#endif
#ifndef _FS_REENTRANT
/** The option \c _FS_REENTRANT switches the re-entrancy (thread-safe) of the
* FatFs module itself. Note that, regardless of this option, file access to
* different volumes is always re-entrant, and the volume control functions,
* \c f_mount(), \c f_mkfs(), and \c f_fdisk(), are always non-re-entrant. Only
* file/directory access to the same volume is under control of this function.
*
* \c 0: Disable re-entrancy. \c _FS_TIMEOUT and \c _SYNC_t have no effect.
* \c 1: Enable re-entrancy. The user-provided synchronization handlers,
* \c ff_req_grant(), \c ff_rel_grant(), \c ff_del_syncobj(), and
* \c ff_cre_syncobj(), must also be added to the project. Samples are
* available in <tt>option/syscall.c</tt>.
*
* \c _FS_TIMEOUT defines the timeout period in unit of time tick.
* \c _SYNC_t defines the OS-dependent sync object type, e.g. \c HANDLE, \c ID,
* \c OS_EVENT*, \c SemaphoreHandle_t, etc. A header file for the OS definitions
* needs to be included somewhere in the scope of <tt>ff.h</tt>.
*/
#define _FS_REENTRANT 0
#endif
#ifndef _FS_TIMEOUT
#define _FS_TIMEOUT 1000
#endif
#ifndef _SYNC_t
#define _SYNC_t HANDLE
#endif
/** @} */
/*----------------------------------------------------------------------------*/
#endif /* FFCONF_H_ */
/**
* @}
* @}
*/

Binary file not shown.

After

Width:  |  Height:  |  Size: 613 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 306 KiB

View file

@ -0,0 +1,6 @@
MOTELIST_ZOLERTIA = orion
MODULES += dev/enc28j60
CC2538_ENC28J60_ARCH ?= gpio
WITH_IP64 ?= 1
CFLAGS += -DUIP_FALLBACK_INTERFACE=ip64_uip_fallback_interface
BOARD_SOURCEFILES += board.c enc28j60-arch-$(CC2538_ENC28J60_ARCH).c leds-arch.c

View file

@ -0,0 +1,44 @@
Zolertia Orion Ethernet Router
============================================
![Zolertia Orion Ethernet Router][zolertia-orion-router]
The Zolertia Orion Ethernet Router allows to create IoT applications out-of-the-box, connecting any IPv4/IPv6 service or application to 6LoWPAN wireless networks.
The Orion Router is a capable IPv4/IPv6 routing device, with an Ethernet interface and dual wireless radio, powered either via micro-USB or Power Over Ethernet (POE). The device integrates the ENC28J60 ethernet module, and an external POE module, supporting up to 48VDC.
Orion is compatible with [6lbr](https://github.com/cetic/6lbr/wiki), more information is available at our [Wiki](https://github.com/Zolertia/Resources/wiki/6lbr).
In a nutshell the Orion Router packs the following features:
* ARM Cortex-M3 with 512KB flash and 32KB RAM (16KB retention), 32MHz.
* ISM 2.4-GHz IEEE 802.15.4 & Zigbee compliant.
* ISM 868-, 915-, 920-, 950-MHz ISM/SRD Band.
* RP-SMA connector for a 2.4GHz external antenna
* SMA connector for a 868/915MHz external antenna
* RJ45 ethernet connector
* Ethernet 10BASE-T IPv4/IP64
* AES-128/256, SHA2 Hardware Encryption Engine.
* ECC-128/256, RSA Hardware Acceleration Engine for Secure Key Exchange.
* On-board CP2104/PIC to flash over its micro-USB connector
* User and reset buttons.
* Power on/off button and LED to show power state
* RGB LED to allow more than 7 colour combinations.
* Indoor enclosure
* Layout 40.29 x 73.75 mm
There are ready-to-use examples at `examples/zolertia/zoul/orion`, showing how to deploy an IP64 border router, and connect to services such as [IFTTT (If This Then That)](https://ifttt.com).
Orion Technical documentation
=============
* [Datasheet](https://github.com/Zolertia/Resources/tree/master/Orion%20Ethernet%20Router/Hardware/Revision%20A/Datasheets)
* [Schematics](https://github.com/Zolertia/Resources/tree/master/Orion%20Ethernet%20Router/Hardware/Revision%20A/Schematics)
Orion Ethernet Router pin-out
=============
![Zolertia Orion Ethernet Router pin-out][zolertia-orion-pinout]
[zolertia-orion-pinout]: ../images/orion-pinout.png "Zolertia Orion Router pin-out"
[zolertia-orion-router]: ../images/orion-router-front.png "Zolertia Orion Ethernet Router"

View file

@ -0,0 +1,60 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* Copyright (c) 2016, Zolertia <http://www.zolertia.com>
* 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.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup zolertia-orion-ethernet-router
* @{
*
* \file
* Board-initialisation for the Zolertia Orion Ethernet Router
*
*/
/*---------------------------------------------------------------------------*/
#include "contiki-conf.h"
#include <stdint.h>
#include <string.h>
/*---------------------------------------------------------------------------*/
static void
configure_unused_pins(void)
{
// FIXME
}
/*---------------------------------------------------------------------------*/
void
board_init()
{
configure_unused_pins();
}
/*---------------------------------------------------------------------------*/
/**
* @}
*/

317
platform/zoul/orion/board.h Normal file
View file

@ -0,0 +1,317 @@
/*
* Copyright (c) 2012, Texas Instruments Incorporated - http://www.ti.com/
* Copyright (c) 2016, Zolertia <http://www.zolertia.com>
* 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.
*/
/**
* \addtogroup zoul-platforms
* @{
*
* \defgroup zolertia-orion-ethernet-router Zolertia IoT Orion Ethernet Router
*
* The Zolertia Orion Router includes an Ethernet ENC28J60 controller with
* active POE (power over ethernet), operating over IPv4/IP64. It features a
* dual RF interface (2.4GHz and 863-950MHz) with external antenna connectors,
* a power on/off switch and programable user button.
*
* This file provides connectivity information on LEDs, Buttons, UART and
* other peripherals
*
* @{
*
* \file
* Header file with definitions related to the I/O connections on the Zolertia's
* Orion Ethernet Router, Zoul-based
*
* \note Do not include this file directly. It gets included by contiki-conf
* after all relevant directives have been set.
*/
#ifndef BOARD_H_
#define BOARD_H_
#include "dev/gpio.h"
#include "dev/nvic.h"
/*---------------------------------------------------------------------------*/
/** \name Orion Ethernet Router LED configuration
*
* LEDs on the eth-gw are connected as follows:
* - LED1 (Red) -> PD5
* - LED2 (Green) -> PD4
* - LED3 (Blue) -> PD3
* @{
*/
/*---------------------------------------------------------------------------*/
/* Some files include leds.h before us, so we need to get rid of defaults in
* leds.h before we provide correct definitions */
#undef LEDS_GREEN
#undef LEDS_YELLOW
#undef LEDS_BLUE
#undef LEDS_RED
#undef LEDS_CONF_ALL
/* In leds.h the LEDS_BLUE is defined by LED_YELLOW definition */
#define LEDS_GREEN (1 << 4) /**< LED1 (Green) -> PD4 */
#define LEDS_BLUE (1 << 3) /**< LED2 (Blue) -> PD3 */
#define LEDS_RED (1 << 5) /**< LED3 (Red) -> PD5 */
#define LEDS_CONF_ALL (LEDS_GREEN | LEDS_BLUE | LEDS_RED)
#define LEDS_LIGHT_BLUE (LEDS_GREEN | LEDS_BLUE) /**< Green + Blue (24) */
#define LEDS_YELLOW (LEDS_GREEN | LEDS_RED) /**< Green + Red (48) */
#define LEDS_PURPLE (LEDS_BLUE | LEDS_RED) /**< Blue + Red (40) */
#define LEDS_WHITE LEDS_ALL /**< Green + Blue + Red (56) */
/* Notify various examples that we have LEDs */
#define PLATFORM_HAS_LEDS 1
/** @} */
/*---------------------------------------------------------------------------*/
/** \name USB configuration
*
* The USB pullup for D+ is not included in this platform
*/
#ifdef USB_PULLUP_PORT
#undef USB_PULLUP_PORT
#endif
#ifdef USB_PULLUP_PIN
#undef USB_PULLUP_PIN
#endif
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART configuration
*
* On the eth-gw, the UARTs are connected to the following ports/pins:
*
* - UART0:
* - RX: PA0, connected to CP2104 serial-to-usb converter TX pin
* - TX: PA1, connected to CP2104 serial-to-usb converter RX pin
* - UART1:
* - RX: PC1
* - TX: PC0
* - CTS: not used
* - RTS: not used
*
* We configure the port to use UART0 and UART1, CTS/RTS only for UART1,
* both without a HW pull-up resistor.
* UART0 is not exposed anywhere, UART1 pins are exposed over the JP9 connector.
* @{
*/
#define UART0_RX_PORT GPIO_A_NUM
#define UART0_RX_PIN 0
#define UART0_TX_PORT GPIO_A_NUM
#define UART0_TX_PIN 1
#define UART1_RX_PORT GPIO_C_NUM
#define UART1_RX_PIN 1
#define UART1_TX_PORT GPIO_C_NUM
#define UART1_TX_PIN 0
#define UART1_CTS_PORT (-1)
#define UART1_CTS_PIN (-1)
#define UART1_RTS_PORT (-1)
#define UART1_RTS_PIN (-1)
/** @} */
/*---------------------------------------------------------------------------*/
/** \name Zolertia Orion Router button configuration
*
* Buttons on the eth-gw are connected as follows:
* - BUTTON_USER -> PA3, S1 user button, shared with bootloader
* - BUTTON_RESET -> RESET_N line
* @{
*/
/** BUTTON_USER -> PA3 */
#define BUTTON_USER_PORT GPIO_A_NUM
#define BUTTON_USER_PIN 3
#define BUTTON_USER_VECTOR GPIO_A_IRQn
/* Notify various examples that we have Buttons */
#define PLATFORM_HAS_BUTTON 1
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name ADC configuration
*
* These values configure which CC2538 pins and ADC channels to use for the ADC
* inputs. There pins are suggested as they can be changed, but note that only
* pins from PA can be configured as ADC.
*
* The Zolertia eth-gw, as it is, only allows 3.3VDC sensors.
*
* The internal ADC reference is 1190mV, use either a voltage divider as input,
* or a different voltage reference, like AVDD5 or other externally (AIN7 or
* AIN6).
*
* The ADC1 is exposed over the JP9 connector
* @{
*/
#define ADC_SENSORS_PORT GPIO_A_NUM /**< ADC GPIO control port */
#define ADC_SENSORS_ADC1_PIN 2 /**< ADC1 to PA2, 3V3 */
#define ADC_SENSORS_ADC2_PIN 4 /**< ADC2 to PA4, 3V3 */
#define ADC_SENSORS_ADC3_PIN 5 /**< ADC3 to PA5, 3V3 */
#define ADC_SENSORS_ADC4_PIN 6 /**< ADC4 to PA6, 3V3 */
#define ADC_SENSORS_ADC5_PIN (-1) /**< Not used */
#define ADC_SENSORS_ADC6_PIN (-1) /**< Not used */
#define ADC_SENSORS_MAX 4 /**< PA2, PA4, PA5, PA6 */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name SPI (SSI0) configuration
*
* These values configure which CC2538 pins to use for the SPI (SSI0) lines,
* reserved exclusively for the CC1200 RF transceiver.
* TX -> MOSI, RX -> MISO
* @{
*/
#define SPI0_CLK_PORT GPIO_B_NUM
#define SPI0_CLK_PIN 2
#define SPI0_TX_PORT GPIO_B_NUM
#define SPI0_TX_PIN 1
#define SPI0_RX_PORT GPIO_B_NUM
#define SPI0_RX_PIN 3
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name SPI (SSI1) configuration
*
* These values configure which CC2538 pins to use for the SPI (SSI1) lines,
* reserved exclusively for the ENC28J60 ethernet module. These pins should not
* be used for other use, unless you really know what you are doing
* TX -> MOSI, RX -> MISO
* @{
*/
#define SPI1_CLK_PORT GPIO_C_NUM
#define SPI1_CLK_PIN 4
#define SPI1_TX_PORT GPIO_C_NUM
#define SPI1_TX_PIN 5
#define SPI1_RX_PORT GPIO_C_NUM
#define SPI1_RX_PIN 6
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name I2C configuration
*
* As default there is not a default pin assignment for I2C, change this values
* accordingly if mapping either pin to the I2C controller.
* @{
*/
#define I2C_SCL_PORT GPIO_C_NUM
#define I2C_SCL_PIN 3
#define I2C_SDA_PORT GPIO_C_NUM
#define I2C_SDA_PIN 2
#define I2C_INT_PORT GPIO_D_NUM
#define I2C_INT_PIN 2
#define I2C_INT_VECTOR GPIO_D_IRQn
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name Dual RF interface support
*
* Enables support for dual band operation (both CC1200 and 2.4GHz enabled).
* @{
*/
#define REMOTE_DUAL_RF_ENABLED 1
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name CC1200 configuration
*
* These values configure the required pins to drive the CC1200
* None of the following pins are exposed to any connector, kept for internal
* use only
* @{
*/
#define CC1200_SPI_INSTANCE 0
#define CC1200_SPI_SCLK_PORT SPI0_CLK_PORT
#define CC1200_SPI_SCLK_PIN SPI0_CLK_PIN
#define CC1200_SPI_MOSI_PORT SPI0_TX_PORT
#define CC1200_SPI_MOSI_PIN SPI0_TX_PIN
#define CC1200_SPI_MISO_PORT SPI0_RX_PORT
#define CC1200_SPI_MISO_PIN SPI0_RX_PIN
#define CC1200_SPI_CSN_PORT GPIO_B_NUM
#define CC1200_SPI_CSN_PIN 5
#define CC1200_GDO0_PORT GPIO_B_NUM
#define CC1200_GDO0_PIN 4
#define CC1200_GDO2_PORT GPIO_B_NUM
#define CC1200_GDO2_PIN 0
#define CC1200_RESET_PORT GPIO_C_NUM
#define CC1200_RESET_PIN 7
#define CC1200_GPIOx_VECTOR GPIO_B_IRQn
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name Ethernet ENC28J60 configuration
*
* These values configure the required pins to drive an external Ethernet
* module. The implementation can be SPI or GPIO-based, for the first the SPI1
* controller should be used
* @{
*/
#define ETH_SPI_INSTANCE 1
#define ETH_SPI_CLK_PORT SPI1_CLK_PORT
#define ETH_SPI_CLK_PIN SPI1_CLK_PIN
#define ETH_SPI_MOSI_PORT SPI1_TX_PORT
#define ETH_SPI_MOSI_PIN SPI1_TX_PIN
#define ETH_SPI_MISO_PORT SPI1_RX_PORT
#define ETH_SPI_MISO_PIN SPI1_RX_PIN
#define ETH_SPI_CSN_PORT GPIO_A_NUM
#define ETH_SPI_CSN_PIN 7
#define ETH_INT_PORT GPIO_D_NUM
#define ETH_INT_PIN 0
#define ETH_RESET_PORT GPIO_D_NUM
#define ETH_RESET_PIN 1
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name On-board external WDT
* The Orion Ethernet Router has an external WDT and battery monitor, which
* adds more robustness and prevents the mote to run wild if any unexpected
* problem shows-up.
* The external WDT requires a short pulse (<1ms) to be sent before a 2-second
* period. The battery monitor keeps the device in Reset if the voltage input
* is lower than 2.5V.
* @{
*/
#define EXT_WDT_PORT GPIO_D_NUM
#define EXT_WDT_PIN 5
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name Device string used on startup
* @{
*/
#define BOARD_STRING "Zolertia Orion Ethernet Router"
/** @} */
#endif /* BOARD_H_ */
/**
* @}
* @}
*/

View file

@ -0,0 +1,154 @@
/*
* Copyright (c) 2012-2013, Thingsquare, http://www.thingsquare.com/.
* Copyright (c) 2016, Zolertia <http://www.zolertia.com>
* 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.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup zolertia-orion-ethernet-router
* @{
*
* \defgroup zolertia-eth-arch-gpio Zolertia ENC28J60 GPIO arch
*
* ENC28J60 eth-gw GPIO arch specifics
* @{
*
* \file
* eth-gw GPIO arch specifics
*/
/*---------------------------------------------------------------------------*/
#include "clock.h"
#include "dev/gpio.h"
/*---------------------------------------------------------------------------*/
#define CLK_PORT GPIO_PORT_TO_BASE(ETH_SPI_CLK_PORT)
#define CLK_BIT GPIO_PIN_MASK(ETH_SPI_CLK_PIN)
#define MOSI_PORT GPIO_PORT_TO_BASE(ETH_SPI_MOSI_PORT)
#define MOSI_BIT GPIO_PIN_MASK(ETH_SPI_MOSI_PIN)
#define MISO_PORT GPIO_PORT_TO_BASE(ETH_SPI_MISO_PORT)
#define MISO_BIT GPIO_PIN_MASK(ETH_SPI_MISO_PIN)
#define CSN_PORT GPIO_PORT_TO_BASE(ETH_SPI_CSN_PORT)
#define CSN_BIT GPIO_PIN_MASK(ETH_SPI_CSN_PIN)
#define RESET_PORT GPIO_PORT_TO_BASE(ETH_RESET_PORT)
#define RESET_BIT GPIO_PIN_MASK(ETH_RESET_PIN)
/*---------------------------------------------------------------------------*/
/* Delay in us */
#define DELAY 10
/*---------------------------------------------------------------------------*/
static void
delay(void)
{
clock_delay_usec(DELAY);
}
/*---------------------------------------------------------------------------*/
void
enc28j60_arch_spi_select(void)
{
GPIO_CLR_PIN(CSN_PORT, CSN_BIT);
delay();
}
/*---------------------------------------------------------------------------*/
void
enc28j60_arch_spi_deselect(void)
{
GPIO_SET_PIN(CSN_PORT, CSN_BIT);
}
/*---------------------------------------------------------------------------*/
void
enc28j60_arch_spi_init(void)
{
/* Set all pins to GPIO mode */
GPIO_SOFTWARE_CONTROL(CLK_PORT, CLK_BIT);
GPIO_SOFTWARE_CONTROL(MOSI_PORT, MOSI_BIT);
GPIO_SOFTWARE_CONTROL(MISO_PORT, MISO_BIT);
GPIO_SOFTWARE_CONTROL(CSN_PORT, CSN_BIT);
GPIO_SOFTWARE_CONTROL(RESET_PORT, RESET_BIT);
/* CSN, MOSI, CLK and RESET are output pins */
GPIO_SET_OUTPUT(CSN_PORT, CSN_BIT);
GPIO_SET_OUTPUT(MOSI_PORT, MOSI_BIT);
GPIO_SET_OUTPUT(CLK_PORT, CLK_BIT);
GPIO_SET_OUTPUT(RESET_PORT, RESET_BIT);
/* MISO is an input pin */
GPIO_SET_INPUT(MISO_PORT, MISO_BIT);
/* Enable the device */
GPIO_SET_INPUT(RESET_PORT, RESET_BIT);
/* The CS pin is active low, so we set it high when we haven't
selected the chip. */
enc28j60_arch_spi_deselect();
/* The CLK is active low, we set it high when we aren't using it. */
GPIO_CLR_PIN(CLK_PORT, CLK_BIT);
}
/*---------------------------------------------------------------------------*/
uint8_t
enc28j60_arch_spi_write(uint8_t output)
{
int i;
uint8_t input;
input = 0;
for(i=0; i < 8; i++) {
/* Write data on MOSI pin */
if(output & 0x80) {
GPIO_SET_PIN(MOSI_PORT, MOSI_BIT);
} else {
GPIO_CLR_PIN(MOSI_PORT, MOSI_BIT);
}
output <<= 1;
/* Set clock high */
GPIO_SET_PIN(CLK_PORT, CLK_BIT);
delay();
/* Read data from MISO pin */
input <<= 1;
if(GPIO_READ_PIN(MISO_PORT, MISO_BIT) != 0) {
input |= 0x1;
}
/* Set clock low */
GPIO_CLR_PIN(CLK_PORT, CLK_BIT);
delay();
}
return input;
}
/*---------------------------------------------------------------------------*/
uint8_t
enc28j60_arch_spi_read(void)
{
return enc28j60_arch_spi_write(0);
}
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
*/

View file

@ -0,0 +1,101 @@
/*
* Copyright (c) 2014, CETIC.
* Copyright (c) 2016, Zolertia <http://www.zolertia.com>
* 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.
*
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup zolertia-orion-ethernet-router
* @{
*
* \defgroup zolertia-eth-arch-spi Zolertia ENC28J60 SPI arch
*
* ENC28J60 eth-gw SPI arch specifics
* @{
*
* \file
* eth-gw SPI arch specifics
*/
/*---------------------------------------------------------------------------*/
#include "spi-arch.h"
#include "spi.h"
#include "dev/gpio.h"
/*---------------------------------------------------------------------------*/
#define RESET_PORT GPIO_PORT_TO_BASE(ETH_RESET_PORT)
#define RESET_BIT GPIO_PIN_MASK(ETH_RESET_PIN)
/*---------------------------------------------------------------------------*/
void
enc28j60_arch_spi_init(void)
{
spix_init(ETH_SPI_INSTANCE);
spix_cs_init(ETH_SPI_CSN_PORT, ETH_SPI_CSN_PIN);
spix_set_mode(ETH_SPI_INSTANCE, SSI_CR0_FRF_MOTOROLA, 0, 0, 8);
GPIO_SOFTWARE_CONTROL(RESET_PORT, RESET_BIT);
GPIO_SET_OUTPUT(RESET_PORT, RESET_BIT);
GPIO_SET_INPUT(RESET_PORT, RESET_BIT);
}
/*---------------------------------------------------------------------------*/
void
enc28j60_arch_spi_select(void)
{
SPIX_CS_CLR(ETH_SPI_CSN_PORT, ETH_SPI_CSN_PIN);
}
/*---------------------------------------------------------------------------*/
void
enc28j60_arch_spi_deselect(void)
{
SPIX_CS_SET(ETH_SPI_CSN_PORT, ETH_SPI_CSN_PIN);
}
/*---------------------------------------------------------------------------*/
void
enc28j60_arch_spi_write(uint8_t output)
{
SPIX_WAITFORTxREADY(ETH_SPI_INSTANCE);
SPIX_BUF(ETH_SPI_INSTANCE) = output;
SPIX_WAITFOREOTx(ETH_SPI_INSTANCE);
SPIX_WAITFOREORx(ETH_SPI_INSTANCE);
uint32_t dummy = SPIX_BUF(ETH_SPI_INSTANCE);
(void) dummy;
}
/*---------------------------------------------------------------------------*/
uint8_t
enc28j60_arch_spi_read(void)
{
SPIX_WAITFORTxREADY(ETH_SPI_INSTANCE);
SPIX_BUF(ETH_SPI_INSTANCE) = 0;
SPIX_WAITFOREOTx(ETH_SPI_INSTANCE);
SPIX_WAITFOREORx(ETH_SPI_INSTANCE);
return SPIX_BUF(ETH_SPI_INSTANCE);
}
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
*/

View file

@ -0,0 +1,44 @@
/*
* Copyright (c) 2012, Thingsquare, http://www.thingsquare.com/.
* Copyright (c) 2016, Zolertia <http://www.zolertia.com>
* 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.
*
*/
/*---------------------------------------------------------------------------*/
#ifndef IP64_CONF_H
#define IP64_CONF_H
/*---------------------------------------------------------------------------*/
#include "ip64-eth-interface.h"
/*---------------------------------------------------------------------------*/
#define IP64_CONF_UIP_FALLBACK_INTERFACE ip64_eth_interface
#define IP64_CONF_INPUT ip64_eth_interface_input
#include "enc28j60-ip64-driver.h"
#define IP64_CONF_ETH_DRIVER enc28j60_ip64_driver
/*---------------------------------------------------------------------------*/
#endif /* IP64_CONF_H */

View file

@ -1,2 +1,4 @@
MOTELIST_ZOLERTIA = remote
BOARD_SOURCEFILES += board.c antenna-sw.c rtcc.c power-mgmt.c leds-arch.c
BOARD_SOURCEFILES += board.c antenna-sw.c mmc-arch.c rtcc.c power-mgmt.c leds-arch.c
MODULES += lib/fs/fat lib/fs/fat/option platform/zoul/fs/fat dev/disk/mmc

View file

@ -268,7 +268,7 @@
/** BUTTON_USER -> PA3 */
#define BUTTON_USER_PORT GPIO_A_NUM
#define BUTTON_USER_PIN 3
#define BUTTON_USER_VECTOR NVIC_INT_GPIO_PORT_A
#define BUTTON_USER_VECTOR GPIO_A_IRQn
/* Notify various examples that we have an user button.
* If ADC6 channel is used, then disable the user button
@ -336,7 +336,7 @@
#define I2C_SDA_PIN 2
#define I2C_INT_PORT GPIO_D_NUM
#define I2C_INT_PIN 1
#define I2C_INT_VECTOR NVIC_INT_GPIO_PORT_D
#define I2C_INT_VECTOR GPIO_D_IRQn
/** @} */
/*---------------------------------------------------------------------------*/
/**
@ -395,7 +395,7 @@
#define CC1200_GDO2_PIN 0
#define CC1200_RESET_PORT GPIO_C_NUM
#define CC1200_RESET_PIN 7
#define CC1200_GPIOx_VECTOR NVIC_INT_GPIO_PORT_B
#define CC1200_GPIOx_VECTOR GPIO_B_IRQn
/** @} */
/*---------------------------------------------------------------------------*/
/**
@ -405,6 +405,7 @@
* external module, to be used with SSI1
* @{
*/
#define USD_SPI_INSTANCE 1
#define USD_CLK_PORT SPI1_CLK_PORT
#define USD_CLK_PIN SPI1_CLK_PIN
#define USD_MOSI_PORT SPI1_TX_PORT
@ -454,13 +455,14 @@
* requiring to put the PIC into deep-sleep and waking up at a certain time.
* @{
*/
#define PLATFORM_HAS_RTC 1
#define RTC_SDA_PORT I2C_SDA_PORT
#define RTC_SDA_PIN I2C_SDA_PIN
#define RTC_SCL_PORT I2C_SCL_PORT
#define RTC_SCL_PIN I2C_SCL_PIN
#define RTC_INT1_PORT GPIO_A_NUM
#define RTC_INT1_PIN 4
#define RTC_INT1_VECTOR NVIC_INT_GPIO_PORT_A
#define RTC_INT1_VECTOR GPIO_A_IRQn
/** @} */
/*---------------------------------------------------------------------------*/
/**

View file

@ -1,2 +1,4 @@
MOTELIST_ZOLERTIA = remote
BOARD_SOURCEFILES += board.c antenna-sw.c rtcc.c leds-res-arch.c power-mgmt.c
BOARD_SOURCEFILES += board.c antenna-sw.c mmc-arch.c rtcc.c leds-res-arch.c power-mgmt.c
MODULES += lib/fs/fat lib/fs/fat/option platform/zoul/fs/fat dev/disk/mmc

View file

@ -293,7 +293,7 @@
*/
#define BUTTON_USER_PORT GPIO_A_NUM
#define BUTTON_USER_PIN 3
#define BUTTON_USER_VECTOR NVIC_INT_GPIO_PORT_A
#define BUTTON_USER_VECTOR GPIO_A_IRQn
/* Notify various examples that we have an user button.
* If ADC6 channel is used, then disable the user button
@ -360,7 +360,7 @@
#define I2C_SDA_PIN 2
#define I2C_INT_PORT GPIO_D_NUM
#define I2C_INT_PIN 0
#define I2C_INT_VECTOR NVIC_INT_GPIO_PORT_D
#define I2C_INT_VECTOR GPIO_D_IRQn
/** @} */
/*---------------------------------------------------------------------------*/
/**
@ -419,7 +419,7 @@
#define CC1200_GDO2_PIN 0
#define CC1200_RESET_PORT GPIO_C_NUM
#define CC1200_RESET_PIN 7
#define CC1200_GPIOx_VECTOR NVIC_INT_GPIO_PORT_B
#define CC1200_GPIOx_VECTOR GPIO_B_IRQn
/** @} */
/*---------------------------------------------------------------------------*/
/**
@ -433,6 +433,7 @@
* a microSD in the slot, or when connected to disable the microSD to save power
* @{
*/
#define USD_SPI_INSTANCE 1
#define USD_CLK_PORT SPI1_CLK_PORT
#define USD_CLK_PIN SPI1_CLK_PIN
#define USD_MOSI_PORT SPI1_TX_PORT
@ -481,13 +482,14 @@
*
* @{
*/
#define PLATFORM_HAS_RTC 1
#define RTC_SDA_PORT I2C_SDA_PORT
#define RTC_SDA_PIN I2C_SDA_PIN
#define RTC_SCL_PORT I2C_SCL_PORT
#define RTC_SCL_PIN I2C_SCL_PIN
#define RTC_INT1_PORT GPIO_D_NUM
#define RTC_INT1_PIN 3
#define RTC_INT1_VECTOR NVIC_INT_GPIO_PORT_D
#define RTC_INT1_VECTOR GPIO_D_IRQn
/** @} */
/*---------------------------------------------------------------------------*/
/**