Initial commit of Simplelink rework

This commit is contained in:
Edvard Pettersen 2018-05-08 21:39:20 +02:00
parent 6ce955a71f
commit a76462b908
76 changed files with 1372 additions and 494 deletions

View File

@ -26,7 +26,7 @@ SMALL ?= 1
ifeq ($(SMALL),1)
CFLAGS += -Os
else
CFLAGS += -O2
CFLAGS += -O0
endif
### Use CMSIS and the existing dbg-io from arch/cpu/arm/common

View File

@ -7,7 +7,7 @@ LDFLAGS += -T $(LDSCRIPT)
LDFLAGS += -Wl,--gc-sections,--sort-section=alignment
LDFLAGS += -Wl,-Map=$(@:.elf=-$(TARGET).map),--cref,--no-warn-mismatch
TARGET_LIBFLAGS := $(TARGET_LIBFILES) -gcc -lm -lnosys -lc
TARGET_LIBFLAGS := $(TARGET_LIBFILES) -lc -lgcc -lm -lnosys
OBJCOPY_FLAGS += --gap-fill 0xff

View File

@ -1,3 +1,5 @@
################################################################################
# CC13x0/CC26x0 CPU makefile
CPU_ABS_PATH = arch/cpu/simplelink

View File

@ -0,0 +1,74 @@
################################################################################
# CC13x2/CC26x2 CPU makefile
# ccfg.c comes from the board-specific folder, and startup_cc13xx_cc26xx_gcc.c
# comes from NoRTOS startup folder
CPU_START_SOURCEFILES += ccfg.c startup_cc13xx_cc26xx_gcc.c
EXTERNALDIRS += $(SDK_SOURCE)
EXTERNALDIRS += $(SDK_KERNEL)
EXTERNALDIRS += $(SDK_KERNEL)/startup
EXTERNALDIRS += $(SDK_BOARD_PATH)
EXTERNALDIRS += $(SDK_DEVICE)
### If the user-specified a Node ID, pass a define
ifdef NODEID
DEFINES += IEEE_ADDR_NODE_ID=$(NODEID)
endif
### CPU-dependent source files
CONTIKI_CPU_SOURCEFILES += rtimer-arch.c clock-arch.c
CONTIKI_CPU_SOURCEFILES += watchdog-arch.c putchar-arch.c
CONTIKI_CPU_SOURCEFILES += uart0-arch.c slip-arch.c
CONTIKI_CPU_SOURCEFILES += rf-common.c
CONTIKI_CPU_SOURCEFILES += rf-prop-mode.c rf-prop-settings.c
CONTIKI_CPU_SOURCEFILES += rf-ieee-mode.c rf-ieee-settings.c
CONTIKI_CPU_SOURCEFILES += ieee-addr.c
### CPU-dependent directories
CONTIKI_CPU_DIRS += $(addprefix ../arm/, $(CPU_DIRS))
CONTIKI_CPU_DIRS += . dev rf-settings cc13x2-cc26x2
### CPU-dependent debug source files
DEBUG_IO_SOURCEFILES += dbg-printf.c dbg-snprintf.c dbg-sprintf.c strformat.c
CONTIKI_SOURCEFILES += $(CONTIKI_CPU_SOURCEFILES) $(DEBUG_IO_SOURCEFILES)
ifeq ($(SMALL),0)
TARGET_LIBFILES += $(SDK_KERNEL)/lib/nortos_$(DEVICE_FAMILY_NAME).am4f
TARGET_LIBFILES += $(SDK_DRIVERS)/rf/lib/rf_multiMode_$(DEVICE_FAMILY_NAME).am4f
TARGET_LIBFILES += $(SDK_DRIVERS)/lib/drivers_$(DEVICE_FAMILY_NAME).am4f
TARGET_LIBFILES += $(SDK_DEVICE)/driverlib/bin/gcc/driverlib.lib
else
TARGET_LIBFILES += $(SDK_KERNEL)/lib/nortos_$(DEVICE_FAMILY_NAME).am4fg
TARGET_LIBFILES += $(SDK_DRIVERS)/rf/lib/rf_multiMode_$(DEVICE_FAMILY_NAME).am4fg
TARGET_LIBFILES += $(SDK_DRIVERS)/lib/drivers_$(DEVICE_FAMILY_NAME).am4fg
TARGET_LIBFILES += $(SDK_DEVICE)/driverlib/bin/gcc/driverlib.lib
endif
LDFLAGS += --entry resetISR
LDFLAGS += -static
LDFLAGS += --specs=nano.specs
# NB! The symbol _stack, which points to the stack start, is expected to be defined,
# but should already be defined in the linker script.
LDFLAGS += -Wl,--defsym=_stack_origin=__stack_end
LDFLAGS += -Wl,--defsym=_heap=__heap_start__
LDFLAGS += -Wl,--defsym=_eheap=__heap_end__
LDFLAGS += -Wl,--defsym=STACKSIZE=2048
LDSCRIPT := $(SDK_BOARD_PATH)/$(SDK_BOARD_NAME)_NoRTOS.lds
### Always re-build ieee-addr.o in case the command line passes a new NODEID
FORCE:
$(OBJECTDIR)/ieee-addr.o: ieee-addr.c FORCE | $(OBJECTDIR)
$(TRACE_CC)
$(Q)$(CC) $(CFLAGS) -c $< -o $@
### Always re-build ccfg.c so changes to ccfg-conf.h will apply without having
### to make clean first
$(OBJECTDIR)/ccfg.o: ccfg.c FORCE | $(OBJECTDIR)
$(TRACE_CC)
$(Q)$(CC) $(CFLAGS) -include "ccfg-conf.h" -c $< -o $@
include $(CONTIKI)/arch/cpu/arm/cortex-m/cm4/Makefile.cm4

View File

@ -1,7 +1,7 @@
MODULES += os/net/mac/framer
CPU_ABS_PATH = $(CONTIKI)/arch/cpu/simplelink
CPU_ABS_PATH = $(CONTIKI)/arch/cpu/cc13xx-cc26xx
SDK_SOURCE := $(SIMPLELINK_SDK)/source
# TODO fix switch
@ -23,10 +23,10 @@ EXTERNALDIRS += $(SDK_STARTUP)
CFLAGS += -I$(CPU_ABS_PATH)
CFLAGS += -I$(CPU_ABS_PATH)/source
CFLAGS += -I$(SDK_SOURCE)
CFLAGS += -I$(SDK_DEVICE_SOURCE)
CFLAGS += -I$(SDK_DEVICE_SOposixURCE)
CFLAGS += -I$(SDK_DEVICE_SOURCE)/inc
CFLAGS += -I$(SDK_KERNEL)
CFLAGS += -I$(SDK_KERNEL)/posix
CFLAGS += -I$(SDK_KERNEL)/
LDFLAGS += --entry resetISR
LDFLAGS += -static
@ -37,8 +37,6 @@ LDFLAGS += -Wl,--defsym=_stack_origin=__stack_end
LDFLAGS += -Wl,--defsym=_heap=__heap_start__
LDFLAGS += -Wl,--defsym=_eheap=__heap_end__
SDK_BOARDS :=
ifneq ($(SIMPLELINK_BOARD),CUSTOM)
SDK_BOARDS := $(SDK_SOURCE)/ti/boards
LDSCRIPT = $(SDK_BOARDS)/$(SIMPLELINK_BOARD)/$(SIMPLELINK_BOARD)_NoRTOS.lds

View File

@ -38,8 +38,8 @@
* \file
* CCxxware-specific configuration for the cc26xx-cc13xx CPU family
*/
#ifndef CCXXWARE_CONF_H_
#define CCXXWARE_CONF_H_
#ifndef CCFG_CONF_H_
#define CCFG_CONF_H_
#include "contiki-conf.h"
@ -68,7 +68,7 @@
#define SET_CCFG_CCFG_TAP_DAP_1_WUC_TAP_ENABLE 0x00
#endif
/** @} */
#endif /* CCXXWARE_CONF_H_ */
#endif /* CCFG_CONF_H_ */
/*---------------------------------------------------------------------------*/
/**
* @}

View File

@ -81,7 +81,7 @@
#ifdef IEEE_ADDR_CONF_LOCATION_SECONDARY
#define IEEE_ADDR_LOCATION_SECONDARY IEEE_ADDR_CONF_LOCATION_SECONDARY
#else
#define IEEE_ADDR_LOCATION_SECONDARY 0x0001FFC8 /**< Secondary IEEE address location */
#define IEEE_ADDR_LOCATION_SECONDARY 0x00057FC8 /**< Secondary IEEE address location */
#endif
/** @} */
/*---------------------------------------------------------------------------*/

View File

@ -10,6 +10,7 @@
* 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.
@ -29,27 +30,38 @@
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup srf06-peripherals
* \addtogroup cc26xx-trng
* @{
*
* \file
* Generic module controlling sensors on the SmartRF06EB
*
* This file overrides os/lib/random.c and calls SoC-specific RNG functions
*/
/*---------------------------------------------------------------------------*/
#include <contiki.h>
#include <lib/sensors.h>
/*---------------------------------------------------------------------------*/
#include "button-sensor-arch.h"
#include "als-sensor-arch.h"
#include <driverlib/trng.h>
/*---------------------------------------------------------------------------*/
/* Exports a global symbol to be used by the sensor API */
SENSORS(
&button_select_sensor,
&button_up_sensor,
&button_down_sensor,
&button_left_sensor,
&button_right_sensor,
&als_sensor
);
/**
* \brief Generates a new random number using the hardware TRNG.
* \return The random number.
*/
unsigned short
random_rand(void)
{
return (unsigned short)soc_trng_rand_synchronous() & 0xFFFF;
}
/*---------------------------------------------------------------------------*/
/** @} */
/**
* \brief Function required by the API
* \param seed Ignored.
*/
void
random_init(unsigned short seed)
{
soc_trng_init();
}
/*---------------------------------------------------------------------------*/
/**
* @}
*/

View File

@ -52,7 +52,7 @@
/*---------------------------------------------------------------------------*/
/* Log configuration */
#include "sys/log.h"
#define LOG_MODULE "RF common"
#define LOG_MODULE "RF"
#define LOG_LEVEL LOG_LEVEL_DBG
/*---------------------------------------------------------------------------*/
PROCESS(RF_coreProcess, "SimpleLink RF process");
@ -66,7 +66,7 @@ PROCESS_THREAD(RF_coreProcess, ev, data)
while(1) {
PROCESS_YIELD_UNTIL(ev == PROCESS_EVENT_POLL);
do {
watchdog_periodic();
//watchdog_periodic();
packetbuf_clear();
len = NETSTACK_RADIO.read(packetbuf_dataptr(), PACKETBUF_SIZE);

View File

@ -58,26 +58,31 @@
#include <driverlib/rf_ieee_mailbox.h>
#include <ti/drivers/rf/RF.h>
/*---------------------------------------------------------------------------*/
/* SimpleLink Platform RF dev */
#include "rf-common.h"
#include "dot-15-4g.h"
/*---------------------------------------------------------------------------*/
/* RF settings */
#ifdef IEEE_MODE_CONF_RF_SETTINGS
# define IEEE_MODE_RF_SETTINGS IEEE_MODE_CONF_RF_SETTINGS
# undef IEEE_MODE_CONF_RF_SETTINGS
#else
# define IEEE_MODE_RF_SETTINGS "rf-settings/rf-ieee-settings.h"
#endif
#include IEEE_MODE_RF_SETTINGS
/*---------------------------------------------------------------------------*/
/* Simplelink Platform RF dev */
#include "rf-common.h"
#include "dot-15-4g.h"
/*---------------------------------------------------------------------------*/
#include <stdint.h>
#include <stddef.h>
#include <string.h>
#include <stdio.h>
#include <stdbool.h>
#include <assert.h>
/*---------------------------------------------------------------------------*/
/* Log configuration */
#include "sys/log.h"
#define LOG_MODULE "RF"
#define LOG_LEVEL LOG_LEVEL_NONE
/*---------------------------------------------------------------------------*/
#ifdef NDEBUG
# define PRINTF(...)
#else
@ -89,7 +94,6 @@
/* Configuration to enable/disable auto ACKs in IEEE mode */
#ifdef IEEE_MODE_CONF_AUTOACK
# define IEEE_MODE_AUTOACK IEEE_MODE_CONF_AUTOACK
# undef IEEE_MODE_CONF_AUTOACK
#else
# define IEEE_MODE_AUTOACK 1
#endif /* IEEE_MODE_CONF_AUTOACK */
@ -97,7 +101,6 @@
/* Configuration to enable/disable frame filtering in IEEE mode */
#ifdef IEEE_MODE_CONF_PROMISCOUS
# define IEEE_MODE_PROMISCOUS IEEE_MODE_CONF_PROMISCOUS
# undef IEEE_MODE_CONF_PROMISCOUS
#else
# define IEEE_MODE_PROMISCOUS 0
#endif /* IEEE_MODE_CONF_PROMISCOUS */
@ -105,7 +108,6 @@
/* Configuration to set the RSSI threshold */
#ifdef IEEE_MODE_CONF_RSSI_THRESHOLD
# define IEEE_MODE_RSSI_THRESHOLD IEEE_MODE_CONF_RSSI_THRESHOLD
# undef IEEE_MODE_CONF_RSSI_THRESHOLD
#else
# define IEEE_MODE_RSSI_THRESHOLD 0xA6
#endif /* IEEE_MODE_CONF_RSSI_THRESHOLD */
@ -113,7 +115,6 @@
/* Configuration for default IEEE channel */
#ifdef IEEE_MODE_CONF_CHANNEL
# define IEEE_MODE_CHANNEL IEEE_MODE_CONF_CHANNEL
# undef IEEE_MODE_CONF_CHANNEL
#else
# define IEEE_MODE_CHANNEL RF_CORE_CHANNEL
#endif
@ -121,14 +122,12 @@
/* Configuration for TX power table */
#ifdef TX_POWER_CONF_DRIVER
# define TX_POWER_DRIVER TX_POWER_CONF_DRIVER
# undef TX_POWER_CONF_DRIVER
#else
# define TX_POWER_DRIVER RF_ieeeTxPower
#endif
#ifdef TX_POWER_CONF_COUNT
# define TX_POWER_COUNT TX_POWER_CONF_COUNT
# undef TX_POWER_CONF_COUNT
#else
# define TX_POWER_COUNT RF_ieeeTxPowerLen
#endif
@ -222,7 +221,7 @@ static RxBuf g_rxBufs[RX_BUF_ENTRIES];
/*---------------------------------------------------------------------------*/
/* RAT overflow upkeep */
static struct ctimer g_ratOverflowTimer;
static rtimer_clock_t g_lastRatOverflow;
static rtimer_clock_t g_ratLastOverflow;
static volatile uint32_t g_ratOverflowCount;
#define RAT_RANGE (~(uint32_t)0)
@ -256,27 +255,70 @@ static volatile uint8_t g_lastCorrLqi;
static volatile uint32_t g_lastTimestamp;
/*---------------------------------------------------------------------------*/
typedef enum {
POWER_STATE_ON,
POWER_STATE_OFF,
POWER_STATE_RESTART,
POWER_STATE_ON = (1 << 0),
POWER_STATE_OFF = (1 << 1),
POWER_STATE_RESTART = (1 << 2),
} PowerState;
/*---------------------------------------------------------------------------*/
/* Forward declarations of static functions */
static int on(void);
static int off(void);
static int set_rx(const PowerState);
static int channel_clear(void);
static void check_rat_overflow(void);
static bool rf_is_on(void);
static uint32_t rat_to_timestamp(const uint32_t);
/*---------------------------------------------------------------------------*/
/* Forward declarations of Radio driver functions */
static int init(void);
static int prepare(const void*, unsigned short);
static int transmit(unsigned short);
static int send(const void*, unsigned short);
static int read(void*, unsigned short);
static int channel_clear(void);
static int receiving_packet(void);
static int pending_packet(void);
static int on(void);
static int off(void);
static radio_result_t get_value(radio_param_t, radio_value_t*);
static radio_result_t set_value(radio_param_t, radio_value_t);
static radio_result_t get_object(radio_param_t, void*, size_t);
static radio_result_t set_object(radio_param_t, const void*, size_t);
/*---------------------------------------------------------------------------*/
/* Radio driver object */
const struct radio_driver ieee_mode_driver = {
init,
prepare,
transmit,
send,
read,
channel_clear,
receiving_packet,
pending_packet,
on,
off,
get_value,
set_value,
get_object,
set_object,
};
/*---------------------------------------------------------------------------*/
static void
synth_error_cb(RF_Handle h, RF_CmdHandle ch, RF_EventMask e)
rx_cb(RF_Handle h, RF_CmdHandle ch, RF_EventMask e)
{
if (e & RF_EventRxOk) {
process_poll(&RF_coreProcess);
}
if (e & RF_EventRxBufFull) {
}
}
/*---------------------------------------------------------------------------*/
static void
rf_error_cb(RF_Handle h, RF_CmdHandle ch, RF_EventMask e)
{
// See SWRZ062B: Synth failed to calibrate, CMD_FS must be repeated
if ((ch == RF_ERROR_CMDFS_SYNTH_PROG) &&
(g_vpCmdFs->status == ERROR_SYNTH_PROG)) {
// See SWRA521: Synth failed to calibrate, CMD_FS must be repeated
RF_postCmd(g_rfHandle, (RF_Op*)g_vpCmdFs, RF_PriorityNormal, synth_error_cb, 0);
// Call CMD_FS async, a synth error will trigger rf_error_cb once more
RF_postCmd(g_rfHandle, (RF_Op*)g_vpCmdFs, RF_PriorityNormal, NULL, 0);
}
}
/*---------------------------------------------------------------------------*/
@ -375,7 +417,7 @@ set_channel(uint8_t channel)
g_vpCmdFs->fractFreq = frac;
// Start FS command asynchronously. We don't care when it is finished
RF_postCmd(g_rfHandle, (RF_Op*)g_vpCmdFs, RF_PriorityNormal, synth_error_cb, 0);
RF_postCmd(g_rfHandle, (RF_Op*)g_vpCmdFs, RF_PriorityNormal, NULL, 0);
if (g_vpCmdRx->status == ACTIVE) {
set_rx(POWER_STATE_RESTART);
}
@ -431,7 +473,7 @@ set_send_on_cca(bool enable)
static void
check_rat_overflow(void)
{
const bool was_off = rf_is_on();
const bool was_off = !rf_is_on();
if (was_off) {
RF_runDirectCmd(g_rfHandle, CMD_NOP);
}
@ -446,7 +488,7 @@ check_rat_overflow(void)
// Overflow happens in the last quarter of the RAT range
if (currentValue + RAT_RANGE / 4 < lastValue) {
// Overflow detected
g_lastRatOverflow = RTIMER_NOW();
g_ratLastOverflow = RTIMER_NOW();
g_ratOverflowCount += 1;
}
}
@ -465,11 +507,11 @@ rat_to_timestamp(const uint32_t ratTimestamp)
uint64_t adjustedOverflowCount = g_ratOverflowCount;
// If the timestamp is in the 4th quarter and the last oveflow was recently,
// If the timestamp is in the 4th quarter and the last overflow was recently,
// assume that the timestamp refers to the time before the overflow
if(ratTimestamp > (uint32_t)(RAT_RANGE * 3 / 4)) {
if(RTIMER_CLOCK_LT(RTIMER_NOW(),
g_lastRatOverflow + RAT_OVERFLOW_PERIOD_SECONDS * RTIMER_SECOND / 4)) {
g_ratLastOverflow + RAT_OVERFLOW_PERIOD_SECONDS * RTIMER_SECOND / 4)) {
adjustedOverflowCount -= 1;
}
}
@ -488,6 +530,7 @@ init(void)
RF_Params_init(&params);
// Disable automatic power-down just to not interfere with stack timing
params.nInactivityTimeout = 0;
params.pErrCb = rf_error_cb;
init_rf_params();
init_data_queue();
@ -532,13 +575,13 @@ rf_is_on(void)
static int
set_rx(const PowerState state)
{
if (state == POWER_STATE_OFF || state == POWER_STATE_RESTART) {
if (state & (POWER_STATE_OFF | POWER_STATE_RESTART)) {
// Stop RX gracefully, don't care about the result
const uint8_t stopGracefully = 1;
RF_cancelCmd(g_rfHandle, g_cmdRxHandle, stopGracefully);
}
if (state == POWER_STATE_ON || state == POWER_STATE_RESTART) {
if (state & (POWER_STATE_ON | POWER_STATE_RESTART)) {
if (g_vpCmdRx->status == ACTIVE) {
PRINTF("set_rx(on): already in RX\n");
return CMD_RESULT_OK;
@ -547,11 +590,12 @@ set_rx(const PowerState state)
RF_ScheduleCmdParams schedParams = {
.endTime = 0,
.priority = RF_PriorityNormal,
.bIeeeBgCmd = true,
//.bIeeeBgCmd = true,
};
g_vpCmdRx->status = IDLE;
g_cmdRxHandle = RF_scheduleCmd(g_rfHandle, (RF_Op*)g_vpCmdRx, &schedParams, NULL, 0);
g_cmdRxHandle = RF_scheduleCmd(g_rfHandle, (RF_Op*)g_vpCmdRx, &schedParams, rx_cb,
RF_EventRxOk | RF_EventRxBufFull | RF_EventRxEntryDone);
if ((g_cmdRxHandle == RF_ALLOC_ERROR) || (g_cmdRxHandle == RF_SCHEDULE_CMD_ERROR)) {
PRINTF("transmit: unable to allocate RX command\n");
return CMD_RESULT_ERROR;
@ -573,7 +617,7 @@ transmit_aux(unsigned short transmit_len)
RF_ScheduleCmdParams schedParams = {
.endTime = 0,
.priority = RF_PriorityNormal,
.bIeeeBgCmd = false,
//.bIeeeBgCmd = false,
};
// As IEEE_TX is a FG command, the TX operation will be executed
@ -632,14 +676,14 @@ release_data_entry(void)
rfc_dataEntryGeneral_t *pEntry = (rfc_dataEntryGeneral_t *)g_pRxReadEntry;
// Clear the length byte and set status to 0: "Pending"
pEntry->length = 0;
g_pRxReadEntry[8] = 0;
pEntry->status = DATA_ENTRY_PENDING;
// Set next entry
g_pRxReadEntry = pEntry->pNextEntry;
}
/*---------------------------------------------------------------------------*/
static int
read_frame(void *buf, unsigned short buf_len)
read(void *buf, unsigned short buf_len)
{
volatile rfc_dataEntryGeneral_t *pEntry = (rfc_dataEntryGeneral_t *)g_pRxReadEntry;
@ -654,29 +698,30 @@ read_frame(void *buf, unsigned short buf_len)
}
// FIXME: something is wrong here about length constraints
if (pEntry->length < 4) {
PRINTF("read_frame: frame too short \n");
const uint8_t frame_len = g_pRxReadEntry[8];
if (frame_len < 8) {
PRINTF("read_frame: frame too short len=%d\n", frame_len);
release_data_entry();
return 0;
}
const int frame_len = pEntry->length - 8;
const uint8_t payload_len = frame_len - 8;
if (frame_len > buf_len) {
if (payload_len > buf_len) {
PRINTF("read_frame: frame larger than buffer\n");
release_data_entry();
return 0;
}
const uint8_t *pData = (uint8_t *)&pEntry->data;
const uint8_t *pData = (uint8_t *)&g_pRxReadEntry[9];
memcpy(buf, pData, frame_len);
memcpy(buf, pData, payload_len);
g_lastRssi = (int8_t)(pData[frame_len + 2]);
g_lastCorrLqi = (uint8_t)(pData[frame_len + 3]) & STATUS_CORRELATION;
g_lastRssi = (int8_t)(pData[payload_len + 2]);
g_lastCorrLqi = (uint8_t)(pData[payload_len + 3]) & STATUS_CORRELATION;
uint32_t ratTimestamp;
memcpy(&ratTimestamp, pData + frame_len + 4, sizeof(ratTimestamp));
memcpy(&ratTimestamp, pData + payload_len + 4, sizeof(ratTimestamp));
g_lastTimestamp = rat_to_timestamp(ratTimestamp);
if (!g_bPollMode) {
@ -689,7 +734,7 @@ read_frame(void *buf, unsigned short buf_len)
release_data_entry();
return frame_len;
return payload_len;
}
/*---------------------------------------------------------------------------*/
static int
@ -799,7 +844,8 @@ on(void)
static int
off(void)
{
set_rx(POWER_STATE_OFF);
const uint8_t stopGracefully = 1;
RF_flushCmd(g_rfHandle, RF_CMDHANDLE_FLUSH_ALL, stopGracefully);
RF_yield(g_rfHandle);
ENERGEST_OFF(ENERGEST_TYPE_LISTEN);
@ -825,7 +871,9 @@ get_value(radio_param_t param, radio_value_t *value)
switch (param) {
case RADIO_PARAM_POWER_MODE:
*value = rf_is_on() ? RADIO_POWER_MODE_ON : RADIO_POWER_MODE_OFF;
*value = rf_is_on()
? RADIO_POWER_MODE_ON
: RADIO_POWER_MODE_OFF;
return RADIO_RESULT_OK;
case RADIO_PARAM_CHANNEL:
@ -1076,23 +1124,6 @@ set_object(radio_param_t param, const void *src, size_t size)
}
}
/*---------------------------------------------------------------------------*/
const struct radio_driver ieee_mode_driver = {
init,
prepare,
transmit,
send,
read_frame,
channel_clear,
receiving_packet,
pending_packet,
on,
off,
get_value,
set_value,
get_object,
set_object,
};
/*---------------------------------------------------------------------------*/
/**
* @}
* @}

View File

@ -36,26 +36,27 @@
* Implementation of the arch-specific rtimer functions for the CC13xx/CC26xx
*/
/*---------------------------------------------------------------------------*/
#include <ti/devices/DeviceFamily.h>
#include DeviceFamily_constructPath(driverlib/aon_event.h)
#include DeviceFamily_constructPath(driverlib/aon_rtc.h)
#include DeviceFamily_constructPath(driverlib/interrupt.h)
#include <ti/drivers/dpl/ClockP.h>
#include <driverlib/aon_event.h>
#include <driverlib/aon_rtc.h>
#include <driverlib/interrupt.h>
/*---------------------------------------------------------------------------*/
#include "contiki.h"
/*---------------------------------------------------------------------------*/
#include <stdint.h>
#define RTIMER_RTC_CH AON_RTC_CH1
/*---------------------------------------------------------------------------*/
#define HWIP_RTC_CH AON_RTC_CH0
#define RTIMER_RTC_CH AON_RTC_CH1
/*---------------------------------------------------------------------------*/
static ClockP_Struct gClk;
static ClockP_Handle hClk;
/*---------------------------------------------------------------------------*/
typedef void (*IsrFxn)(void);
typedef void (*HwiDispatchFxn)(void);
static volatile HwiDispatchFxn hwiDispatch = NULL;
/*---------------------------------------------------------------------------*/
/**
* \brief TODO
@ -75,7 +76,7 @@ rtimer_isr_hook(void)
rtimer_run_next();
}
if (hwiDispatch && AONRTCEventGet(AON_RTC_CH0))
if (hwiDispatch && AONRTCEventGet(HWIP_RTC_CH))
{
hwiDispatch();
}
@ -91,6 +92,8 @@ rtimer_isr_hook(void)
void
rtimer_arch_init(void)
{
const bool intkey = IntMasterDisable();
// Create dummy clock to trigger init of the RAM vector table
ClockP_Params clkParams;
ClockP_Params_init(&clkParams);
@ -115,7 +118,12 @@ rtimer_arch_init(void)
IntRegister(INT_AON_RTC_COMB, rtimer_isr_hook);
AONEventMcuWakeUpSet(AON_EVENT_MCU_WU1, AON_EVENT_RTC_CH1);
AONRTCCombinedEventConfig(AON_RTC_CH0 | RTIMER_RTC_CH);
AONRTCCombinedEventConfig(HWIP_RTC_CH | RTIMER_RTC_CH);
if (!intkey)
{
IntMasterEnable();
}
}
/*---------------------------------------------------------------------------*/
/**

View File

@ -38,26 +38,36 @@
/*---------------------------------------------------------------------------*/
#include <Board.h>
#include <ti/drivers/UART.h>
/*---------------------------------------------------------------------------*/
#include <contiki.h>
/*---------------------------------------------------------------------------*/
#include <stdint.h>
#include <stdbool.h>
#include <assert.h>
/*---------------------------------------------------------------------------*/
#include "uart0-arch.h"
/*---------------------------------------------------------------------------*/
static UART_Handle gh_uart;
static volatile uart0_input_cb g_input_cb;
static unsigned char g_char_buf;
static bool g_bIsInit = false;
/*---------------------------------------------------------------------------*/
static void
uart0_cb(UART_Handle handle, void *buf, size_t count)
{
if (!g_input_cb) { return; }
// Save the current callback function, as this might be overwritten after
// the callback is called.
const uart0_input_cb currCb = g_input_cb;
// Call the callback. Note this might reset g_input_cb
currCb(g_char_buf);
if (currCb == g_input_cb)
{
// If the callback pointer didn't change after the call, do another read.
// Else, the uart0_set_callback was called with a different callback pointer
// and triggered an another read.
if (currCb == g_input_cb) {
UART_read(gh_uart, &g_char_buf, 1);
}
}
@ -65,10 +75,16 @@ uart0_cb(UART_Handle handle, void *buf, size_t count)
void
uart0_init(void)
{
if (g_bIsInit) { return; }
g_bIsInit = true;
UART_init();
UART_Params params;
UART_Params_init(&params);
#ifdef SIMPLELINK_UART_CONF_BAUD_RATE
params.baudRate = SIMPLELINK_UART_CONF_BAUD_RATE;
#endif
params.readMode = UART_MODE_CALLBACK;
params.writeMode = UART_MODE_BLOCKING;
params.readCallback = uart0_cb;
@ -76,35 +92,36 @@ uart0_init(void)
params.readReturnMode = UART_RETURN_NEWLINE;
gh_uart = UART_open(Board_UART0, &params);
if (!gh_uart)
{
for (;;) { /* hang */ }
}
assert(gh_uart != NULL);
}
/*---------------------------------------------------------------------------*/
int_fast32_t
uart0_write(const void *buffer, size_t size)
{
if (!gh_uart)
{
if (!g_bIsInit) {
return UART_STATUS_ERROR;
}
return UART_write(gh_uart, buffer, size);
}
/*---------------------------------------------------------------------------*/
void
int_fast32_t
uart0_set_callback(uart0_input_cb input_cb)
{
if (g_input_cb == input_cb) { return; }
if (!g_bIsInit) {
return UART_STATUS_ERROR;
}
if (g_input_cb == input_cb) {
return UART_STATUS_SUCCESS;
}
g_input_cb = input_cb;
if (input_cb)
{
UART_read(gh_uart, &g_char_buf, 1);
if (input_cb) {
return UART_read(gh_uart, &g_char_buf, 1);
}
else
{
else {
UART_readCancel(gh_uart);
return UART_STATUS_SUCCESS;
}
}
/*---------------------------------------------------------------------------*/

View File

@ -66,18 +66,18 @@ void uart0_init(void);
int_fast32_t uart0_write(const void *buffer, size_t size);
/**
* \brief Reads data from the UART interface to a memory buffer.
* \param buffer A pointer to the data buffer.
* \param size Number of bytes to read
* \return Number of bytes that has been written to the buffer. If an
* error occurs, a negative value is returned.
* \brief Sets the callback function for when bytes are received
* on UART0.
* \param input_cb Pointer to the callback function. A valid pointer subscribes
* for UART0 callbacks when bytes are received, while a NULL pointer
* unsubscribes.
* \return 0 for success, negative value for errors.
*/
void uart0_set_callback(uart0_input_cb input_cb);
int_fast32_t uart0_set_callback(uart0_input_cb input_cb);
/** @} */
/*---------------------------------------------------------------------------*/
#endif /* UART0_ARCH_H_ */
/**
* @}
* @}

View File

@ -148,12 +148,12 @@
*
* @{
*/
#ifndef CC26XX_UART_CONF_ENABLE
#define CC26XX_UART_CONF_ENABLE 1 /**< Enable/Disable UART I/O */
#ifndef SIMPLELINK_UART_CONF_ENABLE
#define SIMPLELINK_UART_CONF_ENABLE 1 /**< Enable/Disable UART I/O */
#endif
#ifndef CC26XX_UART_CONF_BAUD_RATE
#define CC26XX_UART_CONF_BAUD_RATE 115200 /**< Default UART0 baud rate */
#ifndef SIMPLELINK_UART_CONF_BAUD_RATE
#define SIMPLELINK_UART_CONF_BAUD_RATE 115200 /**< Default UART0 baud rate */
#endif
/* Enable I/O over the Debugger Devpack - Only relevant for the SensorTag */

View File

@ -1,10 +0,0 @@
CFLAGS += -I$(CPU_ABS_PATH)/cc26x2_cc13x2
CFLAGS += -I$(SDK_KERNEL)
TARGET_LIBFILES += $(SDK_DRIVERS)/rf/lib/rf_multiMode_cc13x2.am4fg
TARGET_LIBFILES += $(SDK_DRIVERS)/lib/drivers_cc13x2.am4fg
TARGET_LIBFILES += $(SDK_KERNEL)/lib/nortos_cc13x2.am4fg
TARGET_LIBFILES += $(SDK_DRIVERLIB)/bin/gcc/driverlib.lib
include $(CONTIKI)/arch/cpu/arm/cortex-m/cm4/Makefile.cm4

View File

@ -1,33 +1,79 @@
################################################################################
# Simplelink Device family switch
# Device name in upper case
DEVICE_UC := $(shell echo $(SIMPLELINK_DEVICE) | tr a-z A-Z)
# A couple of comments:
# - CC26X0R2 is not supported even though it has its own Device SDK, because
# it is a BLE-only chip.
# - CC26X0 overrides the Device Makefile because it doesn't have its own
# Device SDK. Instead, it uses the TI-RTOS SDK, and therefore cannot
# use the same build structure as all other SimpleLink SDK Devices.
# CC13x0/CC26x0 Family
ifeq ($(DEVICE_UC),CC13X0)
FAMILY := cc13x0_cc26x0
CFLAGS += -DDeviceFamily_CC13X0
else ifeq ($(DEVICE_UC),CC26X0)
FAMILY := cc13x0_cc26x0
CFLAGS += -DDeviceFamily_CC26X0
else ifeq ($(DEVICE_UC),CC26X0R2)
FAMILY := cc13x0_cc26x0
CFLAGS += -DDeviceFamily_CC26X0R2
# Device name in lower case (LC)
SIMPLELINK_DEVICE_LC := $(shell echo $(SIMPLELINK_DEVICE) | tr A-Z a-z)
# Device name in upper case (UC)
SIMPLELINK_DEVICE_UC := $(shell echo $(SIMPLELINK_DEVICE) | tr a-z A-Z)
# CC13x2/CC26x2 Family
else ifeq ($(DEVICE_UC),CC13X2)
FAMILY := cc13x2_cc26x2
CFLAGS += -DDeviceFamily_CC13X2
else ifeq ($(DEVICE_UC),CC26X2)
FAMILY := cc13x2_cc26x2
CFLAGS += -DDeviceFamily_CC26X2
################################################################################
# All supported SimpleLink Devices
SIMPLELINK_DEVICES = cc13x0 cc13x2 cc26x0 cc26x2
# Not supported
################################################################################
# CC13X0/CC26X0 Family
# CC13X0
ifeq ($(SIMPLELINK_DEVICE_LC),cc13x0)
PLATFORM_FAMILY_DIR := cc13x0-cc26x0
DEVICE_FAMILY := DeviceFamily_CC13X0
CFLAGS += -D$(DEVICE_FAMILY)
# CC26X0
else ifeq ($(SIMPLELINK_DEVICE_LC),cc26x0)
PLATFORM_FAMILY_DIR := cc13x0-cc26x0
DEVICE_MAKEFILE := cc26x0
DEVICE_FAMILY := DeviceFamily_CC26X0
CFLAGS += -D$(DEVICE_FAMILY)
################################################################################
# CC13X2/CC26X2 Family
# CC13X2
else ifeq ($(SIMPLELINK_DEVICE_LC),cc13x2)
PLATFORM_FAMILY_DIR := cc13x2-cc26x2
DEVICE_FAMILY := DeviceFamily_CC13X2
CFLAGS += -D$(DEVICE_FAMILY)
# CC26X2
else ifeq ($(SIMPLELINK_DEVICE_LC),cc26x2)
PLATFORM_FAMILY_DIR := cc13x2-cc26x2
DEVICE_FAMILY := DeviceFamily_CC26X2
CFLAGS += -D$(DEVICE_FAMILY)
################################################################################
# Specified Device not supported
else
$(error Simplelink Device '$(SIMPLELINK_DEVICE)' is not currently supported)
$(error Simplelink Device '$(SIMPLELINK_DEVICE)' is not supported)
endif
CONTIKI_TARGET_DIRS += $(FAMILY)/dev
################################################################################
# By default, the Device Makefile is common for all Devices in the Device Family
# unless overriden
ifndef DEVICE_MAKEFILE
DEVICE_MAKEFILE := $(PLATFORM_FAMILY_DIR)
endif
# Include the Family-specific makefile
include $(PLATFORM_ABS_PATH)/$(FAMILY)/Makefile.$(FAMILY)
PLATFORM_ROOT_DIR := $(SIMPLELINK_PATH)/$(PLATFORM_FAMILY_DIR)
# Include the Family-specific Makefile
include $(PLATFORM_ROOT_DIR)/Makefile.$(DEVICE_MAKEFILE)
# The dirs in CONTIKI_TARGET_DIRS will be appended the target makefile directory
# in Makefile.include as part of the CONTIKI_TARGET_DIRS_CONCAT variable,
# however, this does not take into account that the Simplelink platform has one
# more indirection of directories based on device families. This fixes the added
# indirection.
CONTIKI_TARGET_DIRS := $(addprefix $(PLATFORM_FAMILY_DIR)/, $(CONTIKI_TARGET_DIRS))
################################################################################
# Rule for printing supported devices
simplelink_devices:
@echo "$(SIMPLELINK_DEVICES) (current: $(SIMPLELINK_DEVICE_LC))"

View File

@ -1,88 +1,33 @@
################################################################################
# SimpleLink MCU platform makefile
################################################################################
# Sanity check of expected symbols
ifndef CONTIKI
$(error CONTIKI not defined! You must specify where CONTIKI resides!)
endif
PLATFORM_ABS_PATH = $(CONTIKI)/arch/platform/simplelink
ifndef SIMPLELINK_SDK
$(error SIMPLELINK_SDK not defined! You must specify where the SimpleLink SDK resides!)
endif
# Find all available boards from the '<sdk>/source/ti/boards directory'
AVAILABLE_BOARDS := $(shell ls -d $(SIMPLELINK_SDK)/source/ti/boards/*)
# Also allow a custom board file in the application project
AVAILABLE_BOARDS += CUSTOM
ifndef SIMPLELINK_DEVICE
$(error SIMPLELINK_DEVICE not defined! You must specify which device you are using!)
endif
ifndef SIMPLELINK_BOARD
$(error SIMPLELINK_BOARD not defined. You must specify a board!$nAvailable boards:$n $(foreach board, $(AVAILABLE_BOARDS), $(board)$n))
$(error SIMPLELINK_BOARD not defined! You must specify which board you are using!)
endif
# Hacky way to emulate line breaks in warnings/errors
# https://stackoverflow.com/questions/17055773/how-to-synthesize-line-breaks-in-gnu-make-warnings-or-errors
define n
################################################################################
# Defines
SIMPLELINK_PATH := $(CONTIKI)/arch/platform/simplelink
endef
# List of all Simplelink SDKs the Contiki Simplelink platform supports
# with the format "simplelink_<device>_sdk". Don't add the version.
# Simply adding a new entry with the name of a new SDK should be enough when
# the necessary implementations have been made.
SUPPORTED_SDKS = \
simplelink_cc13x0_sdk \
simplelink_cc13x2_sdk \
simplelink_cc26x0_sdk \
simplelink_cc26x2_sdk \
simplelink_cc2640r2_sdk \
# The Simplelink SDK name extracted from the file path.
# e.g. C:/ti/simplelink_cc13x0_sdk_1_60_00_21 => simplelink_cc13x0_sdk_1_60_00_21
SDK_NAME := $(notdir $(SIMPLELINK_SDK))
# The stripped name from the Simplelink SDK, i.e. without version number.
# e.g. simplelink_cc13x0_sdk_1_60_00_21 => simplelink_cc13x0_sdk
# Note that the first grep verifies the SDK name is on a valid format,
# and the second grep extracts the stripped name
SDK_NAME_STRIPPED := $(shell echo "$(SDK_NAME)" \
| grep -Po "simplelink_.*?_sdk_[0-9_]+" \
| grep -Po "simplelink_.*?_sdk")
# Verify a valid Simplelink SDK has been supplied.
# Format is "simplelink_<device>_sdk_<version>"
ifeq (,$(SDK_NAME_STRIPPED))
$(error Supplied Simplelink SDK '$(SDK_NAME)' is not valid.$nFormat is "simplelink_<device>_sdk_<version>")
endif
# Verify a supported Simplelink SDK has been supplied, else print all supported SDKs
ifeq (,$(findstring $(SDK_NAME_STRIPPED), $(SUPPORTED_SDKS)))
$(error Simplelink SDK '$(SDK_NAME)' is not supported.$nSupported SDKs:$n $(foreach sdk, $(SUPPORTED_SDKS), $(sdk)_<version>$n))
endif
ifneq ($(findstring $(SIMPLELINK_BOARD),$(AVAILABLE_BOARDS)),$(SIMPLELINK_BOARD))
$(error Board '$(SIMPLELINK_BOARD)' is not valid for the given Simplelink SDK '$(SDK_NAME)'.$nAvailable boards:$n $(foreach board, $(AVAILABLE_BOARDS), $(board)$n))
endif
### Board and BSP selection
CONTIKI_TARGET_DIRS += . dev
CONTIKI_TARGET_SOURCEFILES += platform.c
# Determine which device family and include the corresponding source files
include $(PLATFORM_ABS_PATH)/Makefile.device-family
CONTIKI_SOURCEFILES += $(CONTIKI_TARGET_SOURCEFILES)
include $(SIMPLELINK_PATH)/Makefile.device-family
CLEAN += *.simplelink
### Unless the example dictates otherwise, build without code size optimisations
# Build without code size optimisations, unless the project dictates otherwise
SMALL ?= 0
CONTIKI_CPU = $(CONTIKI)/arch/cpu/simplelink
include $(CONTIKI_CPU)/Makefile.simplelink
MODULES += os/net os/net/mac os/net/mac/framer

View File

@ -0,0 +1,106 @@
################################################################################
# SimpleLink MCU platform makefile
# Make sure path to Simplelink SDK is specified as absolute path
SIMPLELINK_SDK := $(abspath $(SIMPLELINK_SDK))
################################################################################
# Device Family
# The DeviceFamily.h file will always be available and can therefore be
# hard-coded.
DEVICE_FAMILY_H := $(SIMPLELINK_SDK)/source/ti/devices/DeviceFamily.h
# The define of the Device Family ID is on the format of either
# #define DeviceFamily_ID_<device> <number>
# or
# #define DeviceFamily_ID_<device> <sub-device-family-id>
# We are interested in the right-hand side of the define, i.e. the third word on the line,
# as it either defines a number or an another Device Family ID.
DEVICE_DEFINE := $(shell cat $(DEVICE_FAMILY_H) \
| grep "\#define DeviceFamily_ID_$(SIMPLELINK_DEVICE_UC)\\b" \
| awk '{print $$3}')
# If the define is a number, then the device family name is the resulting device name;
# Else, it points to a sub-name of the device family, e.g. DeviceFamily_ID_CC13X2_V1.
# This line checks if the extracted define is a number or not, based on this SO post:
# https://stackoverflow.com/a/19116862/5099169
IS_NUMBER := $(shell if [ "$(DEVICE_DEFINE)" -eq "$(DEVICE_DEFINE)" ] 2>/dev/null; then echo 1 ; else echo 0 ; fi)
ifeq ($(IS_NUMBER),1)
# The define points to a number, meaning the device family name is the same as the
# specified device name in lower case, e.g.
# cc13x2
DEVICE_FAMILY_NAME := $(SIMPLELINK_DEVICE_LC)
else
# The define points to a sub-name of the device family. The resulting device family name
# is therefore the name after specified after ID in lower case, e.g.
# DeviceFamily_ID_CC13X2_V1
# will result in
# cc13x2_v1
DEVICE_FAMILY_NAME := $(shell echo "$(DEVICE_DEFINE)" \
| sed -E "s/DeviceFamily_ID_(.+)/\1/" \
| tr A-Z a-z )
endif
# The DeviceFamily_constructPath() macro in DeviceFamily.h will always construct the
# correct path for device specific files. In this case, constructing the device specific
# root path. Note that the returned path is encased in angular brackets, <...>,
# and is therefore extracted with sed.
SDK_DEVICE_DIR := $(shell echo "DeviceFamily_constructPath(dummy)" \
| gcc -x c -E -D$(DEVICE_FAMILY) -include $(DEVICE_FAMILY_H) - \
| tail -1 \
| sed -E "s:<(.+)/dummy>:\1:")
################################################################################
# Simplelink SDK paths
SDK_KERNEL := $(SIMPLELINK_SDK)/kernel/nortos
SDK_SOURCE := $(SIMPLELINK_SDK)/source
SDK_BOARDS := $(SDK_SOURCE)/ti/boards
SDK_DRIVERS := $(SDK_SOURCE)/ti/drivers
SDK_DEVICE := $(SDK_SOURCE)/$(SDK_DEVICE_DIR)
################################################################################
# Board and BSP selection
BOARD_TYPES = launchpad sensortag srf06
SIMPLELINK_BOARDS := $(foreach BOARD_TYPE,$(BOARD_TYPES),\
$(shell ls -d $(PLATFORM_ROOT_DIR)/$(BOARD_TYPE)/*/ \
| sed 's/.$$//' \
| rev \
| cut -d / -f -2 \
| rev))
ifeq ($(filter $(SIMPLELINK_BOARD),$(SIMPLELINK_BOARDS)),)
$(error Simplelink Board '$(SIMPLELINK_BOARD)' is not supported for Device '$(SIMPLELINK_DEVICE)')
endif
################################################################################
# Directory and source configurations
# Add to the source dirs
CONTIKI_TARGET_DIRS += .
CONTIKI_TARGET_DIRS += common
CONTIKI_TARGET_DIRS += $(shell echo $(dir $(SIMPLELINK_BOARD)) | sed 's:/$$::')
# Include the board-specific Makefile
include $(PLATFORM_ROOT_DIR)/$(SIMPLELINK_BOARD)/Makefile.$(notdir $(SIMPLELINK_BOARD))
CONTIKI_TARGET_SOURCEFILES += platform.c
CONTIKI_TARGET_SOURCEFILES += $(BOARD_SOURCEFILES)
CONTIKI_SOURCEFILES += $(CONTIKI_TARGET_SOURCEFILES)
# Define the CPU directory and pull in the correct CPU makefile. This will
# be defined by one of the makefiles included above and it can be either
# Makefile.cc26xx or Makefile.cc13xx
CONTIKI_CPU := $(CONTIKI)/arch/cpu/cc13xx-cc26xx
include $(CONTIKI_CPU)/Makefile.cc13x0-cc26x0
MODULES += os/net os/net/mac os/net/mac/framer
################################################################################
# Display all supported Boards for the given
simplelink_boards:
@echo "$(SIMPLELINK_BOARDS) (current: $(SIMPLELINK_BOARD))"

View File

@ -0,0 +1,12 @@
################################################################################
# SimpleLink LaunchPad makefile
DEFINES += BOARD_LAUNCHPAD=1
# leds-arch.c/h etc.
BOARD_SOURCEFILES += launchpad-sensors.c button-sensor-arch.c leds-arch.c
CONTIKI_TARGET_DIRS += launchpad
### Signal that we can be programmed with cc2538-bsl
BOARD_SUPPORTS_BSL=1

View File

@ -0,0 +1,22 @@
################################################################################
# SimpleLink Device makefile
SDK_BOARD_NAME := CC1310_LAUNCHXL
SDK_BOARD_PATH := $(SDK_BOARDS)/$(SDK_BOARD_NAME)
SDK_BOARD_PATH_EXISTS := $(shell test ! -d $(SDK_BOARD_PATH); echo $$?)
ifeq ($(SDK_BOARD_PATH_EXISTS),0)
$(error Simplelink Board '$(SIMPLELINK_BOARD)' is not supported by the specified Simplelink SDK)
endif
DEFINES += SUPPORTS_PROP_MODE=1
DEFINES += SUPPORTS_IEEE_MODE=0
# Add to the source dirs
BOARD_SOURCEFILES += $(SDK_BOARD_NAME).c
EXTERNALDIRS += $(SDK_BOARD_PATH)
# Include the common launchpad makefile
include $(PLATFORM_ROOT_DIR)/launchpad/Makefile.launchpad

View File

@ -0,0 +1,22 @@
################################################################################
# SimpleLink Device makefile
SDK_BOARD_NAME := CC1350_LAUNCHXL_433
SDK_BOARD_PATH := $(SDK_BOARDS)/$(SDK_BOARD_NAME)
SDK_BOARD_PATH_EXISTS := $(shell test ! -d $(SDK_BOARD_PATH); echo $$?)
ifeq ($(SDK_BOARD_PATH_EXISTS),0)
$(error Simplelink Board '$(SIMPLELINK_BOARD)' is not supported by the specified Simplelink SDK)
endif
DEFINES += SUPPORTS_PROP_MODE=1
DEFINES += SUPPORTS_IEEE_MODE=1
# Add to the source dirs
BOARD_SOURCEFILES += $(SDK_BOARD_NAME).c
EXTERNALDIRS += $(SDK_BOARD_PATH)
# Include the common launchpad makefile
include $(PLATFORM_ROOT_DIR)/launchpad/Makefile.launchpad

View File

@ -0,0 +1,22 @@
################################################################################
# SimpleLink Device makefile
SDK_BOARD_NAME := CC1350_LAUNCHXL
SDK_BOARD_PATH := $(SDK_BOARDS)/$(SDK_BOARD_NAME)
SDK_BOARD_PATH_EXISTS := $(shell test ! -d $(SDK_BOARD_PATH); echo $$?)
ifeq ($(SDK_BOARD_PATH_EXISTS),0)
$(error Simplelink Board '$(SIMPLELINK_BOARD)' is not supported by the specified Simplelink SDK)
endif
DEFINES += SUPPORTS_PROP_MODE=1
DEFINES += SUPPORTS_IEEE_MODE=1
# Add to the source dirs
BOARD_SOURCEFILES += $(SDK_BOARD_NAME).c
EXTERNALDIRS += $(SDK_BOARD_PATH)
# Include the common launchpad makefile
include $(PLATFORM_ROOT_DIR)/launchpad/Makefile.launchpad

View File

@ -0,0 +1,22 @@
################################################################################
# SimpleLink Device makefile
SDK_BOARD_NAME := CC2650_LAUNCHXL
SDK_BOARD_PATH := $(SDK_BOARDS)/$(SDK_BOARD_NAME)
SDK_BOARD_PATH_EXISTS := $(shell test ! -d $(SDK_BOARD_PATH); echo $$?)
ifeq ($(SDK_BOARD_PATH_EXISTS),0)
$(error Simplelink Board '$(SIMPLELINK_BOARD)' is not supported by the specified Simplelink SDK)
endif
DEFINES += SUPPORTS_PROP_MODE=0
DEFINES += SUPPORTS_IEEE_MODE=1
# Add to the source dirs
BOARD_SOURCEFILES += $(SDK_BOARD_NAME).c
EXTERNALDIRS += $(SDK_BOARD_PATH)
# Include the common launchpad makefile
include $(PLATFORM_ROOT_DIR)/launchpad/Makefile.launchpad

View File

@ -66,6 +66,7 @@
#include "dev/serial-line.h"
#include "dev/leds.h"
#include "net/mac/framer/frame802154.h"
#include "lib/sensors.h"
/*---------------------------------------------------------------------------*/
/* Arch driver implementations */
#include "uart0-arch.h"
@ -74,7 +75,6 @@
#include "ieee-addr.h"
#include "dev/rf-common.h"
#include "lib/random.h"
#include "lib/sensors.h"
#include "button-sensor.h"
/*---------------------------------------------------------------------------*/
#include <stdio.h>
@ -82,7 +82,7 @@
/* Log configuration */
#include "sys/log.h"
#define LOG_MODULE "CC26xx/CC13xx"
#define LOG_LEVEL LOG_LEVEL_MAIN
#define LOG_LEVEL LOG_LEVEL_DBG
/*---------------------------------------------------------------------------*/
unsigned short g_nodeId = 0;
/*---------------------------------------------------------------------------*/
@ -169,10 +169,17 @@ platform_init_stage_one(void)
void
platform_init_stage_two(void)
{
#if SIMPLELINK_UART_CONF_ENABLE
uart0_init();
#endif
serial_line_init();
// random_init(0x1234);
#if BUILD_WITH_SHELL
uart0_set_callback(serial_line_input_byte);
#endif
// random_init(0x1234);
/* Populate linkaddr_node_addr */
ieee_addr_cpy_to(linkaddr_node_addr.u8, LINKADDR_SIZE);
@ -192,16 +199,15 @@ platform_init_stage_three(void)
LOG_DBG("With DriverLib v%u.%u\n", DRIVERLIB_RELEASE_GROUP,
DRIVERLIB_RELEASE_BUILD);
//LOG_INFO(BOARD_STRING "\n");
LOG_DBG("IEEE 802.15.4: %s, Sub-GHz: %s, BLE: %s, Prop: %s\n",
ChipInfo_SupportsIEEE_802_15_4() ? "Yes" : "No",
ChipInfo_ChipFamilyIs_CC13x0() ? "Yes" : "No",
ChipInfo_SupportsBLE() ? "Yes" : "No",
ChipInfo_SupportsPROPRIETARY() ? "Yes" : "No");
LOG_INFO(" RF: Channel %d, PANID 0x%04X\n", chan, pan);
LOG_INFO(" Node ID: %d\n", g_nodeId);
//
// process_start(&sensors_process, NULL);
LOG_INFO("RF: Channel %d, PANID 0x%04X\n", chan, pan);
LOG_INFO("Node ID: %d\n", g_nodeId);
process_start(&sensors_process, NULL);
fade(LEDS_GREEN);
}
/*---------------------------------------------------------------------------*/

View File

@ -0,0 +1,12 @@
################################################################################
# SimpleLink LaunchPad makefile
DEFINES += BOARD_SENSORTAG=1
# leds-arch.c/h etc.
BOARD_SOURCEFILES += sensortag-sensors.c button-sensor-arch.c leds-arch.c
CONTIKI_TARGET_DIRS += sensortag
### Signal that we can be programmed with cc2538-bsl
BOARD_SUPPORTS_BSL=1

View File

@ -0,0 +1,22 @@
################################################################################
# SimpleLink Device makefile
SDK_BOARD_NAME := CC1350STK
SDK_BOARD_PATH := $(SDK_BOARDS)/$(SDK_BOARD_NAME)
SDK_BOARD_PATH_EXISTS := $(shell test ! -d $(SDK_BOARD_PATH); echo $$?)
ifeq ($(SDK_BOARD_PATH_EXISTS),0)
$(error Simplelink Board '$(SIMPLELINK_BOARD)' is not supported by the specified Simplelink SDK)
endif
DEFINES += SUPPORTS_PROP_MODE=1
DEFINES += SUPPORTS_IEEE_MODE=1
# Add to the source dirs
BOARD_SOURCEFILES += $(SDK_BOARD_NAME).c
EXTERNALDIRS += $(SDK_BOARD_PATH)
# Include the common launchpad makefile
include $(PLATFORM_ROOT_DIR)/sensortag/Makefile.sensortag

View File

@ -0,0 +1,22 @@
################################################################################
# SimpleLink Device makefile
SDK_BOARD_NAME := CC2650STK
SDK_BOARD_PATH := $(SDK_BOARDS)/$(SDK_BOARD_NAME)
SDK_BOARD_PATH_EXISTS := $(shell test ! -d $(SDK_BOARD_PATH); echo $$?)
ifeq ($(SDK_BOARD_PATH_EXISTS),0)
$(error Simplelink Board '$(SIMPLELINK_BOARD)' is not supported by the specified Simplelink SDK)
endif
DEFINES += SUPPORTS_PROP_MODE=0
DEFINES += SUPPORTS_IEEE_MODE=1
# Add to the source dirs
BOARD_SOURCEFILES += $(SDK_BOARD_NAME).c
EXTERNALDIRS += $(SDK_BOARD_PATH)
# Include the common launchpad makefile
include $(PLATFORM_ROOT_DIR)/sensortag/Makefile.sensortag

View File

@ -0,0 +1,12 @@
################################################################################
# SimpleLink LaunchPad makefile
DEFINES += BOARD_SMARTRF06EB=1
# leds-arch.c/h etc.
BOARD_SOURCEFILES += srf06-sensors.c button-sensor-arch.c leds-arch.c
CONTIKI_TARGET_DIRS += srf06
### Signal that we can be programmed with cc2538-bsl
BOARD_SUPPORTS_BSL=1

View File

@ -0,0 +1,22 @@
################################################################################
# SimpleLink Device makefile
SDK_BOARD_NAME := CC1310DK_7XD
SDK_BOARD_PATH := $(SDK_BOARDS)/$(SDK_BOARD_NAME)
SDK_BOARD_PATH_EXISTS := $(shell test ! -d $(SDK_BOARD_PATH); echo $$?)
ifeq ($(SDK_BOARD_PATH_EXISTS),0)
$(error Simplelink Board '$(SIMPLELINK_BOARD)' is not supported by the specified Simplelink SDK)
endif
DEFINES += SUPPORTS_PROP_MODE=1
DEFINES += SUPPORTS_IEEE_MODE=0
# Add to the source dirs
BOARD_SOURCEFILES += $(SDK_BOARD_NAME).c
EXTERNALDIRS += $(SDK_BOARD_PATH)
# Include the common srf06 makefile
include $(PLATFORM_ROOT_DIR)/srf06/Makefile.srf06

View File

@ -0,0 +1,22 @@
################################################################################
# SimpleLink Device makefile
SDK_BOARD_NAME := CC1350DK_7XD
SDK_BOARD_PATH := $(SDK_BOARDS)/$(SDK_BOARD_NAME)
SDK_BOARD_PATH_EXISTS := $(shell test ! -d $(SDK_BOARD_PATH); echo $$?)
ifeq ($(SDK_BOARD_PATH_EXISTS),0)
$(error Simplelink Board '$(SIMPLELINK_BOARD)' is not supported by the specified Simplelink SDK)
endif
DEFINES += SUPPORTS_PROP_MODE=1
DEFINES += SUPPORTS_IEEE_MODE=1
# Add to the source dirs
BOARD_SOURCEFILES += $(SDK_BOARD_NAME).c
EXTERNALDIRS += $(SDK_BOARD_PATH)
# Include the common srf06 makefile
include $(PLATFORM_ROOT_DIR)/srf06/Makefile.srf06

View File

@ -0,0 +1,22 @@
################################################################################
# SimpleLink Device makefile
SDK_BOARD_NAME := CC2650DK_7ID
SDK_BOARD_PATH := $(SDK_BOARDS)/$(SDK_BOARD_NAME)
SDK_BOARD_PATH_EXISTS := $(shell test ! -d $(SDK_BOARD_PATH); echo $$?)
ifeq ($(SDK_BOARD_PATH_EXISTS),0)
$(error Simplelink Board '$(SIMPLELINK_BOARD)' is not supported by the specified Simplelink SDK)
endif
DEFINES += SUPPORTS_PROP_MODE=0
DEFINES += SUPPORTS_IEEE_MODE=1
# Add to the source dirs
BOARD_SOURCEFILES += $(SDK_BOARD_NAME).c
EXTERNALDIRS += $(SDK_BOARD_PATH)
# Include the common launchpad makefile
include $(PLATFORM_ROOT_DIR)/srf06/Makefile.srf06

View File

@ -1,27 +0,0 @@
# SimpleLink MCU platform makefile
### Board and BSP selection
CONTIKI_TARGET_SOURCEFILES += leds-arch.c
# Launchpad boards
ifneq (,$(findstring LAUNCHXL, $(SIMPLELINK_BOARD)))
CONTIKI_TARGET_SOURCEFILES += launchpad-sensors.c
# Sensortag boards
else ifneq (,$(findstring STK, $(SIMPLELINK_BOARD)))
CONTIKI_TARGET_SOURCEFILES += sensortag-sensors.c
# Custom boards
else ifneq (,$(findstring CUSTOM, $(SIMPLELINK_BOARD)))
# TODO
CONTIKI_TARGET_SOURCEFILES += custom-sensors.c
# Everything else is assumed to be EVMs for the SmartRF06 EB (srf06)
else
CONTIKI_TARGET_SOURCEFILES += srf06-sensors.c
endif
CONTIKI_TARGET_SOURCEFILES += button-sensor-arch.c

View File

@ -0,0 +1,103 @@
################################################################################
# SimpleLink MCU platform makefile
# Make sure path to Simplelink SDK is specified as absolute path
SIMPLELINK_SDK := $(abspath $(SIMPLELINK_SDK))
################################################################################
# Device Family
DEVICE_FAMILY_H := $(SIMPLELINK_SDK)/source/ti/devices/DeviceFamily.h
# The define of the Device Family ID is on the format of either
# #define DeviceFamily_ID_<device> <number>
# or
# #define DeviceFamily_ID_<device> <sub-device-family-id>
# We are interested in the right-hand side of the define, i.e. the third word on the line,
# as it either defines a number or an another Device Family ID.
DEVICE_DEFINE := $(shell cat $(DEVICE_FAMILY_H) \
| grep "\#define DeviceFamily_ID_$(SIMPLELINK_DEVICE_UC)\\b" \
| awk '{print $$3}')
# If the define is a number, then the device family name is the resulting device name;
# Else, it points to a sub-name of the device family, e.g. DeviceFamily_ID_CC13X2_V1.
# This line checks if the extracted define is a number or not, based on this SO post:
# https://stackoverflow.com/a/19116862/5099169
IS_NUMBER := $(shell if [ "$(DEVICE_DEFINE)" -eq "$(DEVICE_DEFINE)" ] 2>/dev/null; then echo 1 ; else echo 0 ; fi)
ifeq ($(IS_NUMBER),1)
# The define points to a number, meaning the device family name is the same as the
# specified device name in lower case, e.g.
# cc13x2
DEVICE_FAMILY_NAME := $(SIMPLELINK_DEVICE_LC)
else
# The define points to a sub-name of the device family. The resulting device family name
# is therefore the name after specified after ID in lower case, e.g.
# DeviceFamily_ID_CC13X2_V1
# will result in
# cc13x2_v1
DEVICE_FAMILY_NAME := $(shell echo "$(DEVICE_DEFINE)" \
| sed -E "s/DeviceFamily_ID_(.+)/\1/" \
| tr A-Z a-z )
endif
# The DeviceFamily_constructPath() macro in DeviceFamily.h will always construct the
# correct path for device specific files. In this case, constructing the device specific
# root path. Note that the returned path is encased in angular brackets, <...>,
# and is therefore extracted with sed.
SDK_DEVICE_DIR := $(shell echo "DeviceFamily_constructPath(dummy)" \
| gcc -x c -E -D$(DEVICE_FAMILY) -include $(DEVICE_FAMILY_H) - \
| tail -1 \
| sed -E "s:<(.+)/dummy>:\1:")
################################################################################
# Simplelink SDK paths
SDK_KERNEL := $(SIMPLELINK_SDK)/kernel/nortos
SDK_SOURCE := $(SIMPLELINK_SDK)/source
SDK_BOARDS := $(SDK_SOURCE)/ti/boards
SDK_DRIVERS := $(SDK_SOURCE)/ti/drivers
SDK_DEVICE := $(SDK_SOURCE)/$(SDK_DEVICE_DIR)
################################################################################
# Board and BSP selection
BOARD_TYPES = launchpad
SIMPLELINK_BOARDS := $(foreach BOARD_TYPE, $(BOARD_TYPES), \
$(shell ls -d $(PLATFORM_ROOT_DIR)/$(BOARD_TYPES)/*/ \
| sed 's/.$$//' \
| rev \
| cut -d / -f -2 \
| rev))
ifeq ($(filter $(SIMPLELINK_BOARD),$(SIMPLELINK_BOARDS)),)
$(error Simplelink Board '$(SIMPLELINK_BOARD)' is not supported for Device '$(SIMPLELINK_DEVICE)')
endif
################################################################################
# Directory and source configurations
# Add to the source dirs
CONTIKI_TARGET_DIRS += .
CONTIKI_TARGET_DIRS += common
CONTIKI_TARGET_DIRS += $(shell echo $(dir $(SIMPLELINK_BOARD)) | sed 's:/$$::')
# Include the board-specific Makefile
include $(PLATFORM_ROOT_DIR)/$(SIMPLELINK_BOARD)/Makefile.$(notdir $(SIMPLELINK_BOARD))
CONTIKI_TARGET_SOURCEFILES += platform.c
CONTIKI_TARGET_SOURCEFILES += $(BOARD_SOURCEFILES)
CONTIKI_SOURCEFILES += $(CONTIKI_TARGET_SOURCEFILES)
# Define the CPU directory and pull in the correct CPU makefile. This will
# be defined by one of the makefiles included above and it can be either
# Makefile.cc26xx or Makefile.cc13xx
CONTIKI_CPU=$(CONTIKI)/arch/cpu/cc13xx-cc26xx
include $(CONTIKI_CPU)/Makefile.cc13x2-cc26x2
MODULES += os/net os/net/mac os/net/mac/framer
################################################################################
# Display all supported Boards for the given
simplelink_boards:
@echo "$(SIMPLELINK_BOARDS) (current: $(SIMPLELINK_BOARD))"

View File

@ -1,5 +1,5 @@
/*
* Copyright (c) 2016, University of Bristol - http://www.bris.ac.uk/
* Copyright (c) 2018 Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
@ -29,20 +29,38 @@
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup srf06-common-peripherals
* \addtogroup simplelink-platform
* @{
*
* \defgroup simplelink-button-sensor Simplelink Button Driver
*
* One of the buttons can be configured as general purpose or as an on/off key
* @{
*
* \file
* Header file for the SmartRF06EB + CC13xx/CC26xxEM ALS Driver
* Header file for the Simplelink Button Driver
*/
/*---------------------------------------------------------------------------*/
#ifndef ALS_SENSOR_H_
#define ALS_SENSOR_H_
#ifndef BUTTON_SENSOR_H_
#define BUTTON_SENSOR_H_
/*---------------------------------------------------------------------------*/
#include "lib/sensors.h"
/* Contiki API */
#include <lib/sensors.h>
/*---------------------------------------------------------------------------*/
extern const struct sensors_sensor als_sensor;
/* Board specific button sensors */
#include "button-sensor-arch.h"
/*---------------------------------------------------------------------------*/
#endif /* ALS_SENSOR_H_ */
#define BUTTON_SENSOR "Button"
/*---------------------------------------------------------------------------*/
/** @} */
#define BUTTON_SENSOR_VALUE_STATE 0
#define BUTTON_SENSOR_VALUE_DURATION 1
#define BUTTON_SENSOR_VALUE_RELEASED 0
#define BUTTON_SENSOR_VALUE_PRESSED 1
/*---------------------------------------------------------------------------*/
#endif /* BUTTON_SENSOR_H_ */
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
*/

View File

@ -0,0 +1,78 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.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 cc26xx-srf-tag
* @{
*
* \file
* Configuration for the srf06-cc26xx platform
*/
#ifndef CONTIKI_CONF_H
#define CONTIKI_CONF_H
#include <stdint.h>
/*---------------------------------------------------------------------------*/
/* Include Project Specific conf */
#ifdef PROJECT_CONF_PATH
#include PROJECT_CONF_PATH
#endif /* PROJECT_CONF_PATH */
/*---------------------------------------------------------------------------*/
#include "simplelink-def.h"
/*---------------------------------------------------------------------------*/
/**
* \name Button configurations
*
* Configure a button as power on/off: We use the right button for both boards.
* @{
*/
#ifndef BUTTON_SENSOR_CONF_ENABLE_SHUTDOWN
#define BUTTON_SENSOR_CONF_ENABLE_SHUTDOWN 1
#endif
/* Notify various examples that we have Buttons */
#define PLATFORM_HAS_BUTTON 1
/*
* Override button symbols from dev/button-sensor.h, for the examples that
* include it
*/
#define button_sensor button_left_sensor
#define button_sensor2 button_right_sensor
/** @} */
/*---------------------------------------------------------------------------*/
/* Platform-specific define to signify sensor reading failure */
#define CC26XX_SENSOR_READING_ERROR 0x80000000
/*---------------------------------------------------------------------------*/
/* Include CPU-related configuration */
#include "simplelink-conf.h"
/*---------------------------------------------------------------------------*/
#endif /* CONTIKI_CONF_H */
/** @} */

View File

@ -0,0 +1,12 @@
################################################################################
# SimpleLink LaunchPad makefile
DEFINES += BOARD_LAUNCHPAD=1
# leds-arch.c/h etc.
BOARD_SOURCEFILES += launchpad-sensors.c button-sensor-arch.c leds-arch.c
CONTIKI_TARGET_DIRS += launchpad
### Signal that we can be programmed with cc2538-bsl
BOARD_SUPPORTS_BSL=0

View File

@ -49,13 +49,10 @@
#include "button-sensor.h"
#include "button-sensor-arch.h"
/*---------------------------------------------------------------------------*/
/* SmartRF06 EB has 5 buttons: Select, Up, Down, Left, and Right */
/* LaunchPad has 2 buttons: BTN1 and BTN2 */
/* Map the GPIO defines from the Board file */
#define BUTTON_SELECT_GPIO Board_KEY_SELECT
#define BUTTON_UP_GPIO Board_KEY_UP
#define BUTTON_DOWN_GPIO Board_KEY_DOWN
#define BUTTON_LEFT_GPIO Board_KEY_LEFT
#define BUTTON_RIGHT_GPIO Board_KEY_RIGHT
#define BTN1_GPIO Board_GPIO_BTN1
#define BTN2_GPIO Board_GPIO_BTN2
/*---------------------------------------------------------------------------*/
#ifdef BUTTON_SENSOR_CONF_ENABLE_SHUTDOWN
# define BUTTON_SENSOR_ENABLE_SHUTDOWN BUTTON_SENSOR_CONF_ENABLE_SHUTDOWN
@ -71,11 +68,8 @@ typedef struct {
clock_time_t duration;
} BtnTimer;
/*---------------------------------------------------------------------------*/
static BtnTimer g_buttonSelectTimer;
static BtnTimer g_buttonUpTimer;
static BtnTimer g_buttonDownTimer;
static BtnTimer g_buttonLeftTimer;
static BtnTimer g_buttonRightTimer;
static BtnTimer g_btn1Timer;
static BtnTimer g_btn2Timer;
/*---------------------------------------------------------------------------*/
static void
button_press_cb(uint8_t index, BtnTimer *btnTimer, const struct sensors_sensor *btnSensor)
@ -145,150 +139,60 @@ button_status(int type, uint8_t index)
return 0;
}
/*---------------------------------------------------------------------------*/
/* Select Button */
static void
btn1_press_cb(unsigned char unusued)
{
button_press_cb(BTN1_GPIO, &g_btn1Timer, &btn1_sensor);
}
/*---------------------------------------------------------------------------*/
static int
btn1_value(int type)
{
return button_value(type, BTN1_GPIO, &g_btn1Timer);
}
/*---------------------------------------------------------------------------*/
static int
btn1_config(int type, int value)
{
return button_config(type, value, BTN1_GPIO, btn1_press_cb);
}
/*---------------------------------------------------------------------------*/
static int
btn1_status(int type)
{
return button_status(type, BTN1_GPIO);
}
/*---------------------------------------------------------------------------*/
static void
button_select_press_cb(unsigned char unusued)
{
button_press_cb(BUTTON_SELECT_GPIO, &g_buttonSelectTimer, &button_select_sensor);
}
/*---------------------------------------------------------------------------*/
static int
button_select_value(int type)
{
return button_value(type, BUTTON_SELECT_GPIO, &g_buttonSelectTimer);
}
/*---------------------------------------------------------------------------*/
static int
button_select_config(int type, int value)
{
return button_config(type, value, BUTTON_SELECT_GPIO, button_select_press_cb);
}
/*---------------------------------------------------------------------------*/
static int
button_select_status(int type)
{
return button_status(type, BUTTON_SELECT_GPIO);
}
/*---------------------------------------------------------------------------*/
/* Up Button */
/*---------------------------------------------------------------------------*/
static void
button_up_press_cb(unsigned char unusued)
{
button_press_cb(BUTTON_UP_GPIO, &g_buttonUpTimer, &button_up_sensor);
}
/*---------------------------------------------------------------------------*/
static int
button_up_value(int type)
{
return button_value(type, BUTTON_UP_GPIO, &g_buttonUpTimer);
}
/*---------------------------------------------------------------------------*/
static int
button_up_config(int type, int value)
{
return button_config(type, value, BUTTON_UP_GPIO, button_up_press_cb);
}
/*---------------------------------------------------------------------------*/
static int
button_up_status(int type)
{
return button_status(type, BUTTON_UP_GPIO);
}
/*---------------------------------------------------------------------------*/
/* Down Button */
/*---------------------------------------------------------------------------*/
static void
button_down_press_cb(unsigned char unusued)
{
button_press_cb(BUTTON_DOWN_GPIO, &g_buttonDownTimer, &button_down_sensor);
}
/*---------------------------------------------------------------------------*/
static int
button_down_value(int type)
{
return button_value(type, BUTTON_DOWN_GPIO, &g_buttonDownTimer);
}
/*---------------------------------------------------------------------------*/
static int
button_down_config(int type, int value)
{
return button_config(type, value, BUTTON_DOWN_GPIO, button_down_press_cb);
}
/*---------------------------------------------------------------------------*/
static int
button_down_status(int type)
{
return button_status(type, BUTTON_DOWN_GPIO);
}
/*---------------------------------------------------------------------------*/
/* Left Button */
/*---------------------------------------------------------------------------*/
static void
button_left_press_cb(unsigned char unusued)
{
button_press_cb(BUTTON_LEFT_GPIO, &g_buttonLeftTimer, &button_left_sensor);
}
/*---------------------------------------------------------------------------*/
static int
button_left_value(int type)
{
return button_value(type, BUTTON_LEFT_GPIO, &g_buttonLeftTimer);
}
/*---------------------------------------------------------------------------*/
static int
button_left_config(int type, int value)
{
return button_config(type, value, BUTTON_LEFT_GPIO, button_left_press_cb);
}
/*---------------------------------------------------------------------------*/
static int
button_left_status(int type)
{
return button_status(type, BUTTON_LEFT_GPIO);
}
/*---------------------------------------------------------------------------*/
/* Right Button */
/*---------------------------------------------------------------------------*/
static void
button_right_press_cb(unsigned char unusued)
btn2_press_cb(unsigned char unusued)
{
if (BUTTON_SENSOR_ENABLE_SHUTDOWN) {
Power_shutdown(Power_ENTERING_SHUTDOWN, 0);
return;
}
button_press_cb(BUTTON_RIGHT_GPIO, &g_buttonRightTimer, &button_right_sensor);
button_press_cb(BTN2_GPIO, &g_btn2Timer, &btn2_sensor);
}
/*---------------------------------------------------------------------------*/
static int
button_right_value(int type)
btn2_value(int type)
{
return button_value(type, BUTTON_RIGHT_GPIO, &g_buttoRightimer);
return button_value(type, BTN2_GPIO, &g_btn2Timer);
}
/*---------------------------------------------------------------------------*/
static int
button_right_config(int type, int value)
btn2_config(int type, int value)
{
return button_config(type, value, BUTTON_RIGHT_GPIO, button_right_press_cb);
return button_config(type, value, BTN2_GPIO, btn2_press_cb);
}
/*---------------------------------------------------------------------------*/
static int
button_right_status(int type)
btn2_status(int type)
{
return button_status(type, BUTTON_RIGHT_GPIO);
return button_status(type, BTN1_GPIO);
}
/*---------------------------------------------------------------------------*/
SENSORS_SENSOR(button_select_sensor, BUTTON_SENSOR,
button_select_value, button_select_config, button_select_status);
SENSORS_SENSOR(button_up_sensor, BUTTON_SENSOR,
button_up_value, button_up_config, button_up_status);
SENSORS_SENSOR(button_down_sensor, BUTTON_SENSOR,
button_down_value, button_down_config, button_down_status);
SENSORS_SENSOR(button_left_sensor, BUTTON_SENSOR,
button_left_value, button_left_config, button_left_status);
SENSORS_SENSOR(button_right_sensor, BUTTON_SENSOR,
button_right_value, button_right_config, button_right_status);
SENSORS_SENSOR(btn1_sensor, BUTTON_SENSOR, btn1_value, btn1_config, btn1_status);
SENSORS_SENSOR(btn2_sensor, BUTTON_SENSOR, btn2_value, btn2_config, btn2_status);
/*---------------------------------------------------------------------------*/
/** @} */

View File

@ -47,11 +47,8 @@
/* Contiki API */
#include <lib/sensors.h>
/*---------------------------------------------------------------------------*/
extern const struct sensors_sensor button_select_sensor;
extern const struct sensors_sensor button_up_sensor;
extern const struct sensors_sensor button_down_sensor;
extern const struct sensors_sensor button_left_sensor;
extern const struct sensors_sensor button_right_sensor;
extern const struct sensors_sensor btn1_sensor;
extern const struct sensors_sensor btn2_sensor;
/*---------------------------------------------------------------------------*/
#endif /* BUTTON_SENSOR_ARCH_H_ */
/*---------------------------------------------------------------------------*/

View File

@ -0,0 +1,22 @@
################################################################################
# SimpleLink Device makefile
SDK_BOARD_NAME := CC1312R1_LAUNCHXL
SDK_BOARD_PATH := $(SDK_BOARDS)/$(SDK_BOARD_NAME)
SDK_BOARD_PATH_EXISTS := $(shell test ! -d $(SDK_BOARD_PATH); echo $$?)
ifeq ($(SDK_BOARD_PATH_EXISTS),0)
$(error Simplelink Board '$(SIMPLELINK_BOARD)' is not supported by the specified Simplelink SDK)
endif
DEFINES += SUPPORTS_PROP_MODE=1
DEFINES += SUPPORTS_IEEE_MODE=0
# Add to the source dirs
BOARD_SOURCEFILES += $(SDK_BOARD_NAME).c
EXTERNALDIRS += $(SDK_BOARD_PATH)
# Include the common launchpad makefile
include $(PLATFORM_ROOT_DIR)/launchpad/Makefile.launchpad

View File

@ -0,0 +1,22 @@
################################################################################
# SimpleLink Device makefile
SDK_BOARD_NAME := CC1352P1_LAUNCHXL
SDK_BOARD_PATH := $(SDK_BOARDS)/$(SDK_BOARD_NAME)
SDK_BOARD_PATH_EXISTS := $(shell test ! -d $(SDK_BOARD_PATH); echo $$?)
ifeq ($(SDK_BOARD_PATH_EXISTS),0)
$(error Simplelink Board '$(SIMPLELINK_BOARD)' is not supported by the specified Simplelink SDK)
endif
DEFINES += SUPPORTS_PROP_MODE=1
DEFINES += SUPPORTS_IEEE_MODE=1
# Add to the source dirs
BOARD_SOURCEFILES += $(SDK_BOARD_NAME).c
EXTERNALDIRS += $(SDK_BOARD_PATH)
# Include the common launchpad makefile
include $(PLATFORM_ROOT_DIR)/launchpad/Makefile.launchpad

View File

@ -0,0 +1,22 @@
################################################################################
# SimpleLink Device makefile
SDK_BOARD_NAME := CC1352R1_LAUNCHXL
# Check that the provided Simplelink SDK supports this device. Simply checking
# whether a folder with the name of $(SDK_BOARD_NAME) exists in the board folder
# is sufficient, # i.e. folder exists in <SDK>/source/ti/boards.
SDK_BOARD_PATH := $(SDK_BOARDS)/$(SDK_BOARD_NAME)
SDK_BOARD_PATH_EXISTS := $(shell test ! -d $(SDK_BOARD_PATH); echo $$?)
ifeq ($(SDK_BOARD_PATH_EXISTS),0)
$(error Simplelink Board '$(SIMPLELINK_BOARD)' is not supported by the specified Simplelink SDK)
endif
DEFINES += SUPPORTS_PROP_MODE=1
DEFINES += SUPPORTS_IEEE_MODE=1
# Add to the source dirs
BOARD_SOURCEFILES += $(SDK_BOARD_NAME).c
# Include the common launchpad makefile
include $(PLATFORM_ROOT_DIR)/launchpad/Makefile.launchpad

View File

@ -0,0 +1,22 @@
################################################################################
# SimpleLink Device makefile
SDK_BOARD_NAME := CC26X2R1_LAUNCHXL
SDK_BOARD_PATH := $(SDK_BOARDS)/$(SDK_BOARD_NAME)
SDK_BOARD_PATH_EXISTS := $(shell test ! -d $(SDK_BOARD_PATH); echo $$?)
ifeq ($(SDK_BOARD_PATH_EXISTS),0)
$(error Simplelink Board '$(SIMPLELINK_BOARD)' is not supported by the specified Simplelink SDK)
endif
DEFINES += SUPPORTS_PROP_MODE=0
DEFINES += SUPPORTS_IEEE_MODE=1
# Add to the source dirs
BOARD_SOURCEFILES += $(SDK_BOARD_NAME).c
EXTERNALDIRS += $(SDK_BOARD_PATH)
# Include the common launchpad makefile
include $(PLATFORM_ROOT_DIR)/launchpad/Makefile.launchpad

View File

@ -39,12 +39,17 @@
#include <contiki.h>
#include <lib/sensors.h>
/*---------------------------------------------------------------------------*/
#include "button-sensor-arch.h"
#include "button-sensor.h"
/*---------------------------------------------------------------------------*/
/* Exports a global symbol to be used by the sensor API */
SENSORS(
&btn1_sensor,
&btn2_sensor
#ifdef BUTTON_SENSOR_ARCH_BTN1
&button_sensor,
#endif
#ifdef BUTTON_SENSOR_ARCH_BTN2
&button_sensor2,
#endif
NULL
);
/*---------------------------------------------------------------------------*/
/** @} */

View File

@ -1,5 +1,5 @@
/*
* Copyright (c) 2016, University of Bristol - http://www.bris.ac.uk/
* Copyright (c) 2018, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
@ -29,71 +29,106 @@
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup srf06-common-peripherals
* \addtogroup simplelink-platform
* @{
*
* \file
* Driver for the SmartRF06EB ALS when a CC13xx/CC26xxEM is mounted on it
* Driver for LaunchPad LEDs
*/
/*---------------------------------------------------------------------------*/
/* Contiki API */
#include <contiki.h>
#include <lib/sensors.h>
#include <sys/clock.h>
#include <dev/leds.h>
/*---------------------------------------------------------------------------*/
/* Simplelink SDK API */
#include <Board.h>
#include <driverlib/aux_adc.h>
#include <driverlib/ioc.h>
#include <driverlib/gpio.h>
/*---------------------------------------------------------------------------*/
#include "als-sensor.h"
#include "als-sensor-arch.h"
#include <ti/drivers/GPIO.h>
/*---------------------------------------------------------------------------*/
/* Standard library */
#include <stdbool.h>
#include <stdint.h>
/*---------------------------------------------------------------------------*/
/* SmartRF06 EB has one Analog Light Sensor (ALS) */
#define ALS_OUT_DIO Board_ALS_OUT
#define ALS_PWR_DIO Board_ALS_PWR
/*---------------------------------------------------------------------------*/
static int
config(int type, int value)
{
switch (type) {
case SENSORS_ACTIVE:
IOCPinTypeGpioOutput(ALS_PWR_DIO);
IOCPortConfigureSet(ALS_OUT_DIO, IOC_PORT_GPIO, IOC_STD_OUTPUT);
IOCPinTypeGpioInput(ALS_OUT_DIO);
/* Available LED configuration */
if (value) {
GPIO_setDio(ALS_PWR_DIO);
AUXADCSelectInput(ALS_OUT_DIO);
clock_delay_usec(2000);
} else {
GPIO_clearDio(ALS_PWR_DIO);
}
break;
/* Green LED */
#ifdef Board_GPIO_GLED
# define LEDS_ARCH_GREEN Board_GPIO_GLED
#endif
/* Yellow LED */
#ifdef Board_GPIO_YLED
# define LEDS_ARCH_YELLOW Board_GPIO_YLED
#endif
/* Red LED */
#ifdef Board_GPIO_RLED
# define LEDS_ARCH_RED Board_GPIO_RLED
#endif
/* Blue LED */
#ifdef Board_GPIO_BLED
# define LEDS_ARCH_BLUE Board_GPIO_BLED
#endif
/*---------------------------------------------------------------------------*/
static unsigned char c;
/*---------------------------------------------------------------------------*/
void
leds_arch_init(void)
{
static bool bHasInit = false;
if(bHasInit) {
return;
}
return 1;
bHasInit = true;
// GPIO_init will most likely be called in platform.c,
// but call it here to be sure GPIO is initialized.
// Calling GPIO_init multiple times is safe.
GPIO_init();
}
/*---------------------------------------------------------------------------*/
static int
value(int type)
unsigned char
leds_arch_get(void)
{
AUXADCEnableSync(AUXADC_REF_VDDS_REL, AUXADC_SAMPLE_TIME_2P7_US, AUXADC_TRIGGER_MANUAL);
AUXADCGenManualTrigger();
int val = AUXADCReadFifo();
AUXADCDisable();
return val;
return c;
}
/*---------------------------------------------------------------------------*/
static int
status(int type)
static inline void
write_led(const bool on, const uint_fast32_t gpioLed)
{
return 1;
const GPIO_PinConfig pinCfg = (on)
? Board_GPIO_LED_ON : Board_GPIO_LED_OFF;
GPIO_write(gpioLed, pinCfg);
}
/*---------------------------------------------------------------------------*/
SENSORS_SENSOR(als_sensor, ALS_SENSOR, value, config, status);
void
leds_arch_set(unsigned char leds)
{
c = leds;
#define LED_ON(led_define) ((leds & (led_define)) == (led_define))
// Green LED
#ifdef LEDS_ARCH_GREEN
write_led(LED_ON(LEDS_GREEN), LEDS_ARCH_GREEN);
#endif
// Yellow LED
#ifdef LEDS_ARCH_YELLOW
write_led(LED_ON(LEDS_YELLOW), LEDS_ARCH_YELLOW);
#endif
// Red LED
#ifdef LEDS_ARCH_RED
write_led(LED_ON(LEDS_RED), LEDS_ARCH_RED);
#endif
// Blue LED
#ifdef LEDS_ARCH_BLUE
write_led(LED_ON(LEDS_BLUE), LEDS_ARCH_BLUE);
#endif
#undef LED_ON
}
/*---------------------------------------------------------------------------*/
/** @} */

View File

@ -0,0 +1,224 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.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 cc13xx-cc26xx-platforms
* @{
*
* \defgroup LaunchPads
*
* This platform supports a number of different boards:
* - The TI CC1310 LaunchPad
* - The TI CC1350 LaunchPad
* - The TI CC2640 LaunchPad
* - The TI CC2650 LaunchPad
* - The TI CC1312R1 LaunchPad
* - The TI CC1352R1 LaunchPad
* - The TI CC1352P1 LaunchPad
* - The TI CC26X2R1 LaunchPad
* @{
*/
/*---------------------------------------------------------------------------*/
/* Simplelink SDK includes */
#include <Board.h>
#include <ti/drivers/GPIO.h>
#include <ti/drivers/Power.h>
#include <driverlib/driverlib_release.h>
#include <driverlib/chipinfo.h>
#include <driverlib/vims.h>
#include <driverlib/interrupt.h>
#include <NoRTOS.h>
/*---------------------------------------------------------------------------*/
/* Contiki API */
#include "contiki.h"
#include "contiki-net.h"
#include "sys/clock.h"
#include "sys/rtimer.h"
#include "sys/node-id.h"
#include "sys/platform.h"
#include "dev/serial-line.h"
#include "dev/leds.h"
#include "net/mac/framer/frame802154.h"
#include "lib/sensors.h"
/*---------------------------------------------------------------------------*/
/* Arch driver implementations */
#include "uart0-arch.h"
/*---------------------------------------------------------------------------*/
//#include "gpio-interrupt.h"
#include "ieee-addr.h"
#include "dev/rf-common.h"
#include "lib/random.h"
#include "button-sensor.h"
/*---------------------------------------------------------------------------*/
#include <stdio.h>
/*---------------------------------------------------------------------------*/
/* Log configuration */
#include "sys/log.h"
#define LOG_MODULE "CC26xx/CC13xx"
#define LOG_LEVEL LOG_LEVEL_DBG
/*---------------------------------------------------------------------------*/
unsigned short g_nodeId = 0;
/*---------------------------------------------------------------------------*/
/** \brief Board specific initialization */
void board_init(void);
/*---------------------------------------------------------------------------*/
static void
fade(unsigned char l)
{
volatile int i;
for(int k = 0; k < 800; ++k) {
int j = k > 400 ? 800 - k : k;
leds_on(l);
for(i = 0; i < j; ++i) {
__asm("nop");
}
leds_off(l);
for(i = 0; i < 400 - j; ++i) {
__asm("nop");
}
}
}
/*---------------------------------------------------------------------------*/
static void
set_rf_params(void)
{
uint16_t short_addr;
uint8_t ext_addr[8];
ieee_addr_cpy_to(ext_addr, sizeof(ext_addr));
short_addr = ext_addr[7];
short_addr |= ext_addr[6] << 8;
NETSTACK_RADIO.set_value(RADIO_PARAM_PAN_ID, IEEE802154_PANID);
NETSTACK_RADIO.set_value(RADIO_PARAM_16BIT_ADDR, short_addr);
NETSTACK_RADIO.set_value(RADIO_PARAM_CHANNEL, RF_CORE_CHANNEL);
NETSTACK_RADIO.set_object(RADIO_PARAM_64BIT_ADDR, ext_addr, sizeof(ext_addr));
/* also set the global node id */
g_nodeId = short_addr;
}
/*---------------------------------------------------------------------------*/
void
platform_init_stage_one(void)
{
// Enable flash cache
VIMSModeSet(VIMS_BASE, VIMS_MODE_ENABLED);
// Configure round robin arbitration and prefetching
VIMSConfigure(VIMS_BASE, true, true);
Board_initGeneral();
GPIO_init();
// NoRTOS_start only enables HWI
NoRTOS_start();
// Contiki drivers init
leds_init();
// ti_lib_int_master_disable();
//
// /* Set the LF XOSC as the LF system clock source */
// oscillators_select_lf_xosc();
//
// lpm_init();
//
fade(LEDS_RED);
//
// /*
// * Disable I/O pad sleep mode and open I/O latches in the AON IOC interface
// * This is only relevant when returning from shutdown (which is what froze
// * latches in the first place. Before doing these things though, we should
// * allow software to first regain control of pins
// */
// ti_lib_pwr_ctrl_io_freeze_disable();
//
// ti_lib_int_master_enable();
//
fade(LEDS_GREEN);
}
/*---------------------------------------------------------------------------*/
void
platform_init_stage_two(void)
{
#if SIMPLELINK_UART_CONF_ENABLE
uart0_init();
#endif
serial_line_init();
#if BUILD_WITH_SHELL
uart0_set_callback(serial_line_input_byte);
#endif
// random_init(0x1234);
/* Populate linkaddr_node_addr */
ieee_addr_cpy_to(linkaddr_node_addr.u8, LINKADDR_SIZE);
fade(LEDS_RED);
}
/*---------------------------------------------------------------------------*/
void
platform_init_stage_three(void)
{
radio_value_t chan, pan;
set_rf_params();
NETSTACK_RADIO.get_value(RADIO_PARAM_CHANNEL, &chan);
NETSTACK_RADIO.get_value(RADIO_PARAM_PAN_ID, &pan);
LOG_DBG("With DriverLib v%u.%u\n", DRIVERLIB_RELEASE_GROUP,
DRIVERLIB_RELEASE_BUILD);
LOG_DBG("IEEE 802.15.4: %s, Sub-GHz: %s, BLE: %s, Prop: %s\n",
ChipInfo_SupportsIEEE_802_15_4() ? "Yes" : "No",
ChipInfo_ChipFamilyIs_CC13x0() ? "Yes" : "No",
ChipInfo_SupportsBLE() ? "Yes" : "No",
ChipInfo_SupportsPROPRIETARY() ? "Yes" : "No");
LOG_INFO("RF: Channel %d, PANID 0x%04X\n", chan, pan);
LOG_INFO("Node ID: %d\n", g_nodeId);
process_start(&sensors_process, NULL);
fade(LEDS_GREEN);
}
/*---------------------------------------------------------------------------*/
void
platform_idle(void)
{
// Drop to some low power mode
Power_idleFunc();
}
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
*/

View File

@ -1,28 +0,0 @@
# SimpleLink MCU platform makefile
### Board and BSP selection
CONTIKI_TARGET_SOURCEFILES += leds-arch.c
# Launchpad boards
ifneq (,$(findstring LAUNCHXL, $(SIMPLELINK_BOARD)))
CONTIKI_TARGET_DIRS += $(FAMILY)/launchpad
CONTIKI_TARGET_SOURCEFILES += button-sensor-arch.c
CONTIKI_TARGET_SOURCEFILES += launchpad-sensors.c
# Custom boards
else ifneq (,$(findstring CUSTOM, $(SIMPLELINK_BOARD)))
# TODO Need to figure out how custom boards are to be provided
CONTIKI_TARGET_DIRS += $(FAMILY)/custom
CONTIKI_TARGET_SOURCEFILES += custom-sensors.c
# Everything else is assumed to be EVMs for the SmartRF06 EB (srf06)
else
CONTIKI_TARGET_DIRS += $(FAMILY)/srf06
CONTIKI_TARGET_SOURCEFILES += button-sensor-arch.c
CONTIKI_TARGET_SOURCEFILES += srf06-sensors.c
endif
CONTIKI_TARGET_SOURCEFILES += button-sensor-arch.c