Merge branch 'develop' into bugfix/gpio/64bit

This commit is contained in:
Simon Duquennoy 2018-10-19 14:08:05 +02:00 committed by GitHub
commit 1df85a12a4
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
84 changed files with 1172 additions and 1473 deletions

View File

@ -3,6 +3,9 @@
# Future extensions to the build system that are of a similar nature (for
# embedded devices only), can be achieved by extending this Makefile here.
###
### Targets using the tools/serial-io
###
RLWRAPGOALS = login serialdump serialview
.PHONY: $(RLWRAPGOALS)
@ -31,3 +34,14 @@ serialview: $(SERIAL_DUMP_BIN)
login: $(SERIAL_DUMP_BIN)
$(SERIALDUMP) -b$(BAUDRATE) $(PORT)
###
### Targets using tools/motelist
###
CONTIKI_NG_MOTELIST_DIR = $(TOOLS_DIR)/motelist
CONTIKI_NG_MOTELIST = python $(CONTIKI_NG_MOTELIST_DIR)/motelist.py
.PHONY: motelist-all
motelist-all:
$(CONTIKI_NG_MOTELIST)

29
Makefile.help Normal file
View File

@ -0,0 +1,29 @@
usage:
@echo "Usage:"
@echo " make [TARGET=(TARGET)] [BOARD=(BOARD)] [DEFINES=(DEFINES)] [PORT=(PORT)] [target]"
@echo ""
@echo "Typical usage:"
@echo " make [TARGET=(TARGET)] [BOARD=(BOARD)] [all]"
@echo ""
@echo " Will build Contiki-NG firmware(s) from the current example dir"
@echo " for platform TARGET, board BOARD."
@echo ""
@echo "Miscellaneous targets:"
@echo " targets Prints list of supported platforms"
@echo " boards Prints a list of supported boards for TARGET"
@echo " savetarget Saves TARGET and BOARD for future invocations of make"
@echo " savedefines Saves DEFINES for future invocations of make"
@echo " clean Removes all compiled files for TARGET"
@echo " distclean Removes all compiled files for all TARGETs"
@echo " viewconf Prints Contiki-NG build configuration for TARGET"
@echo " %.flashprof Shows a Flash/ROM profile of a given firmware (e.g. hello-world.flashprof)"
@echo " %.ramprof Shows a RAM profile of a given firmware (e.g. hello-world.ramprof)"
@echo " %.o Produces an object file from a given source file (e.g. hello-world.o)"
@echo " %.e Produces the pre-processed version of a given source file (e.g. hello-world.e)"
@echo " %.s Produces an assembly file from a given source file (e.g. hello-world.s)"
@echo " login View the serial output of the device connected to PORT"
@echo " serialview Same as login, but prepend serial output with a unix timestamp"
@echo " serialdump same as serialview, but also save the output to a file"
@echo " motelist-all Prints a list of connected devices"
help: usage

View File

@ -46,11 +46,6 @@ UPPERCASE = _ABCDEFGHIJKLMNOPQRSTUVWXYZ_
TARGET_UPPERCASE := ${strip ${shell echo $(TARGET) | sed y!$(LOWERCASE)!$(UPPERCASE)!}}
CFLAGS += -DCONTIKI=1 -DCONTIKI_TARGET_$(TARGET_UPPERCASE)=1
CFLAGS += -DCONTIKI_TARGET_STRING=\"$(TARGET)\"
ifneq ($(BOARD),)
TARGET_BOARD_UPPERCASE := ${strip ${shell echo $(BOARD) | sed y!$(LOWERCASE)!$(UPPERCASE)!}}
CFLAGS += -DCONTIKI_BOARD_$(TARGET_BOARD_UPPERCASE)=1
CFLAGS += -DCONTIKI_BOARD_STRING=\"$(BOARD)\"
endif
CFLAGS += -Wno-unused-const-variable
@ -129,6 +124,12 @@ endif # $(BOARD) not empty
PLATFORM_ACTION ?= build
ifneq ($(BOARD),)
TARGET_BOARD_UPPERCASE := ${strip ${shell echo $(BOARD) | sed y!$(LOWERCASE)!$(UPPERCASE)!}}
CFLAGS += -DCONTIKI_BOARD_$(TARGET_BOARD_UPPERCASE)=1
CFLAGS += -DCONTIKI_BOARD_STRING=\"$(BOARD)\"
endif
# Configure MAC layer
# The different options
@ -394,34 +395,7 @@ endif
%.flashprof: %.$(TARGET)
$(NM) -S -td --size-sort $< | grep -i " [t] " | cut -d' ' -f2,4
usage:
@echo "Usage:"
@echo " make [TARGET=(TARGET)] [BOARD=(BOARD)] [DEFINES=(DEFINES)] [PORT=(PORT)] [target]"
@echo ""
@echo "Typical usage:"
@echo " make [TARGET=(TARGET)] [BOARD=(BOARD)] [all]"
@echo ""
@echo " Will build Contiki-NG firmware(s) from the current example dir"
@echo " for platform TARGET, board BOARD."
@echo ""
@echo "Miscellaneous targets:"
@echo " targets Prints list of supported platforms"
@echo " boards Prints a list of supported boards for TARGET"
@echo " savetarget Saves TARGET and BOARD for future invocations of make"
@echo " savedefines Saves DEFINES for future invocations of make"
@echo " clean Removes all compiled files for TARGET"
@echo " distclean Removes all compiled files for all TARGETs"
@echo " viewconf Prints Contiki-NG build configuration for TARGET"
@echo " %.flashprof Shows a Flash/ROM profile of a given firmware (e.g. hello-world.flashprof)"
@echo " %.ramprof Shows a RAM profile of a given firmware (e.g. hello-world.ramprof)"
@echo " %.o Produces an object file from a given source file (e.g. hello-world.o)"
@echo " %.e Produces the pre-processed version of a given source file (e.g. hello-world.e)"
@echo " %.s Produces an assembly file from a given source file (e.g. hello-world.s)"
@echo " login View the serial output of the device connected to PORT"
@echo " serialview Same as login, but prepend serial output with a unix timestamp"
@echo " serialdump same as serialview, but also save the output to a file"
help: usage
include $(CONTIKI)/Makefile.help
targets:
@ls $(CONTIKI)/arch/platform $(TARGETDIRS)

View File

@ -1,3 +1,14 @@
CONTIKI_ARM_DIRS += cortex-m cortex-m/CMSIS
### Build syscalls for newlib
MODULES += os/lib/newlib
CUSTOM_RULE_LINK = 1
.SECONDEXPANSION:
%.elf: $(CPU_STARTFILES) $$(CONTIKI_OBJECTFILES) %.o $(PROJECT_OBJECTFILES) $(PROJECT_LIBRARIES) $(LDSCRIPT) $(TARGET_LIBS)
$(TRACE_LD)
$(Q)$(LD) $(LDFLAGS) ${filter-out $(LDSCRIPT) %.a,$^} ${filter %.a,$^} $(TARGET_LIBFLAGS) -o $@
include $(CONTIKI)/arch/cpu/arm/Makefile.arm

View File

@ -9,22 +9,10 @@ LDFLAGS += -Wl,-Map=$(CONTIKI_NG_PROJECT_MAP),--cref,--no-warn-mismatch
OBJCOPY_FLAGS += --gap-fill 0xff
### Build syscalls for newlib
MODULES += os/lib/newlib
CPU_STARTFILES = ${addprefix $(OBJECTDIR)/,${call oname, $(CPU_START_SOURCEFILES)}}
### Compilation rules
CUSTOM_RULE_LINK = 1
### Resolve any potential circular dependencies between the linked libraries
### See: https://stackoverflow.com/questions/5651869/gcc-what-are-the-start-group-and-end-group-command-line-options/5651895
TARGET_LIBFLAGS := -Wl,--start-group $(TARGET_LIBFILES) -lm -Wl,--end-group
.SECONDEXPANSION:
%.elf: $(CPU_STARTFILES) $$(CONTIKI_OBJECTFILES) %.o $(PROJECT_OBJECTFILES) $(PROJECT_LIBRARIES) $(LDSCRIPT)
$(TRACE_LD)
$(Q)$(LD) $(LDFLAGS) ${filter-out $(LDSCRIPT) %.a,$^} ${filter %.a,$^} $(TARGET_LIBFLAGS) -o $@
include $(CONTIKI)/arch/cpu/arm/cortex-m/Makefile.cortex-m

View File

@ -9,20 +9,10 @@ LDFLAGS += -Wl,-Map=$(CONTIKI_NG_PROJECT_MAP),--cref,--no-warn-mismatch
OBJCOPY_FLAGS += --gap-fill 0xff
### Build syscalls for newlib
MODULES += os/lib/newlib
CPU_STARTFILES = ${addprefix $(OBJECTDIR)/,${call oname, $(CPU_START_SOURCEFILES)}}
### Compilation rules
CUSTOM_RULE_LINK = 1
### Resolve any potential circular dependencies between the linked libraries
### See: https://stackoverflow.com/questions/5651869/gcc-what-are-the-start-group-and-end-group-command-line-options/5651895
TARGET_LIBFLAGS := -Wl,--start-group $(TARGET_LIBFILES) -Wl,--end-group
%.elf: $(CPU_STARTFILES) %.o $(PROJECT_OBJECTFILES) $(PROJECT_LIBRARIES) $(CONTIKI_NG_TARGET_LIB) $(TARGET_LIBS)
$(TRACE_LD)
$(Q)$(LD) $(LDFLAGS) ${filter %.o %.a,$^} $(TARGET_LIBFLAGS) -o $@
include $(CONTIKI)/arch/cpu/arm/cortex-m/Makefile.cortex-m

View File

@ -36,11 +36,13 @@
/*---------------------------------------------------------------------------*/
#define RTIMER_ARCH_SECOND 32768
/*---------------------------------------------------------------------------*/
#define CC2538_PHY_OVERHEAD 3
#define CC2538_BYTE_AIR_TIME 32
/* 352us from calling transmit() until the SFD byte has been sent */
#define CC2538_DELAY_BEFORE_TX ((unsigned)US_TO_RTIMERTICKS(352))
#define CC2538_DELAY_BEFORE_TX ((unsigned)US_TO_RTIMERTICKS(352))
/* 192us as in datasheet but ACKs are not always received, so adjusted to 250us */
#define CC2538_DELAY_BEFORE_RX ((unsigned)US_TO_RTIMERTICKS(250))
#define CC2538_DELAY_BEFORE_DETECT 0
#define CC2538_DELAY_BEFORE_RX ((unsigned)US_TO_RTIMERTICKS(250))
#define CC2538_DELAY_BEFORE_DETECT 0
/* Frame filtering done in software */
#define TSCH_CONF_HW_FRAME_FILTERING 0

View File

@ -865,6 +865,7 @@ get_value(radio_param_t param, radio_value_t *value)
return RADIO_RESULT_OK;
case RADIO_CONST_PHY_OVERHEAD:
*value = (radio_value_t)3; /* 1 len byte, 2 bytes CRC */
return RADIO_RESULT_OK;
case RADIO_CONST_BYTE_AIR_TIME:
*value = (radio_value_t)32; /* 250kbps data rate. One byte = 32us.*/
return RADIO_RESULT_OK;

View File

@ -281,27 +281,6 @@ spi_arch_close_and_unlock(const spi_device_t *dev)
return SPI_DEV_STATUS_OK;
}
/*---------------------------------------------------------------------------*/
spi_status_t
spi_arch_select(const spi_device_t *dev)
{
if(!spi_arch_has_lock(dev)) {
return SPI_DEV_STATUS_BUS_NOT_OWNED;
}
SPIX_CS_CLR(PIN_TO_PORT(dev->pin_spi_cs), PIN_TO_NUM(dev->pin_spi_cs));
return SPI_DEV_STATUS_OK;
}
/*---------------------------------------------------------------------------*/
spi_status_t
spi_arch_deselect(const spi_device_t *dev)
{
SPIX_CS_SET(PIN_TO_PORT(dev->pin_spi_cs), PIN_TO_NUM(dev->pin_spi_cs));
return SPI_DEV_STATUS_OK;
}
/*---------------------------------------------------------------------------*/
/* Assumes that checking dev and bus is not NULL before calling this */
spi_status_t
spi_arch_transfer(const spi_device_t *dev,

View File

@ -1,7 +1,7 @@
TI_XXWARE_PATH = lib/cc13xxware
CONTIKI_CPU_SOURCEFILES += smartrf-settings.c prop-mode.c prop-mode-tx-power.c
CONTIKI_CPU_SOURCEFILES += smartrf-settings.c prop-mode.c prop-mode-tx-power.c cc13xx-50kbps-tsch.c
CFLAGS += -DCPU_FAMILY_CC13XX=1
CFLAGS += -DCPU_FAMILY_CC13X0=1 -DCPU_FAMILY_CC13XX=1
include $(CONTIKI_CPU)/Makefile.cc26xx-cc13xx

View File

@ -1,3 +1,5 @@
TI_XXWARE_PATH = lib/cc2640r2-sdk
CFLAGS += -DCPU_FAMILY_CC26X0R2=1 -DCPU_FAMILY_CC26XXR2=1
include $(CONTIKI_CPU)/Makefile.cc26xx-cc13xx

View File

@ -1,3 +1,5 @@
TI_XXWARE_PATH = lib/cc26xxware
CFLAGS += -DCPU_FAMILY_CC26X0=1 -DCPU_FAMILY_CC26XX=1
include $(CONTIKI_CPU)/Makefile.cc26xx-cc13xx

View File

@ -1,8 +1,8 @@
CPU_ABS_PATH = arch/cpu/cc26xx-cc13xx
TI_XXWARE = $(CONTIKI_CPU)/$(TI_XXWARE_PATH)
ifeq (,$(wildcard $(TI_XXWARE)))
$(warning $(TI_XXWARE) does not exist.)
ifeq (,$(wildcard $(TI_XXWARE)/*))
$(warning $(TI_XXWARE) does not exist or is empty.)
$(warning Did you run 'git submodule update --init' ?)
$(error "")
endif

View File

@ -64,11 +64,11 @@
* project has specified otherwise. Depending on the final mode, determine a
* default channel (again, if unspecified) and configure RDC params
*/
#if CPU_FAMILY_CC13XX
#if CPU_FAMILY_CC13X0
#ifndef CC13XX_CONF_PROP_MODE
#define CC13XX_CONF_PROP_MODE 1
#endif /* CC13XX_CONF_PROP_MODE */
#endif /* CPU_FAMILY_CC13XX */
#endif /* CPU_FAMILY_CC13X0 */
#if CC13XX_CONF_PROP_MODE
#ifndef NETSTACK_CONF_RADIO

View File

@ -36,12 +36,43 @@
/*---------------------------------------------------------------------------*/
/* TSCH related defines */
/* 2 bytes header, 4 bytes CRC */
#define CC13XX_RADIO_PHY_OVERHEAD 6
/* 3 bytes preamble, 3 bytes sync */
#define CC13XX_RADIO_PHY_HEADER_LEN 6
/* The default data rate is 50 kbps */
#define CC13XX_RADIO_BIT_RATE 50000
/* 1 len byte, 2 bytes CRC */
#define RADIO_PHY_OVERHEAD 3
/* 250kbps data rate. One byte = 32us */
#define RADIO_BYTE_AIR_TIME 32
#define CC26XX_RADIO_PHY_OVERHEAD 3
/* 4 bytes preamble, 1 byte sync */
#define CC26XX_RADIO_PHY_HEADER_LEN 5
/* The fixed data rate is 250 kbps */
#define CC26XX_RADIO_BIT_RATE 250000
#if CPU_FAMILY_CC13XX
#define RADIO_PHY_HEADER_LEN CC13XX_RADIO_PHY_HEADER_LEN
#define RADIO_PHY_OVERHEAD CC13XX_RADIO_PHY_OVERHEAD
#define RADIO_BIT_RATE CC13XX_RADIO_BIT_RATE
/* The TSCH default slot length of 10ms is too short, use custom one instead */
#ifndef TSCH_CONF_DEFAULT_TIMESLOT_TIMING
#define TSCH_CONF_DEFAULT_TIMESLOT_TIMING tsch_timing_cc13xx_50kbps
#endif /* TSCH_CONF_DEFAULT_TIMESLOT_TIMING */
/* Symbol for the custom TSCH timeslot timing template */
#define TSCH_CONF_ARCH_HDR_PATH "rf-core/cc13xx-50kbps-tsch.h"
#else
#define RADIO_PHY_HEADER_LEN CC26XX_RADIO_PHY_HEADER_LEN
#define RADIO_PHY_OVERHEAD CC26XX_RADIO_PHY_OVERHEAD
#define RADIO_BIT_RATE CC26XX_RADIO_BIT_RATE
#endif
#define RADIO_BYTE_AIR_TIME (1000000 / (RADIO_BIT_RATE / 8))
/* Delay between GO signal and SFD */
#define RADIO_DELAY_BEFORE_TX ((unsigned)US_TO_RTIMERTICKS(81))
#define RADIO_DELAY_BEFORE_TX ((unsigned)US_TO_RTIMERTICKS(RADIO_PHY_HEADER_LEN * RADIO_BYTE_AIR_TIME))
/* Delay between GO signal and start listening.
* This value is so small because the radio is constantly on within each timeslot. */
#define RADIO_DELAY_BEFORE_RX ((unsigned)US_TO_RTIMERTICKS(15))
@ -56,9 +87,6 @@
#define RADIO_TO_RTIMER(X) ((uint32_t)(((uint64_t)(X) * (RTIMER_SECOND / 256)) / (RADIO_TIMER_SECOND / 256)))
#define USEC_TO_RADIO(X) ((X) * 4)
/* The PHY header (preamble + SFD, 4+1 bytes) duration is equivalent to 10 symbols */
#define RADIO_IEEE_802154_PHY_HEADER_DURATION_USEC 160
/* Do not turn off TSCH within a timeslot: not enough time */
#define TSCH_CONF_RADIO_ON_DURING_TIMESLOT 1

View File

@ -96,6 +96,8 @@ SECTIONS
/* These symbols are used by the stack check library. */
_stack = .;
_stack_origin = ORIGIN(SRAM) + LENGTH(SRAM);
_heap = _stack;
_eheap = _stack_origin;
.ccfg :
{

View File

@ -39,7 +39,6 @@
/*---------------------------------------------------------------------------*/
#include "contiki.h"
#include "ti-lib.h"
#include "ti-lib-rom.h"
#include "dev/gpio-hal.h"
#include <stdint.h>
@ -53,11 +52,7 @@ gpio_hal_arch_pin_cfg_set(gpio_hal_pin_t pin, gpio_hal_pin_cfg_t cfg)
gpio_hal_pin_cfg_t tmp;
/* Clear settings that we are about to change, keep everything else */
#ifdef ThisLibraryIsFor_CC26x0R2_HaltIfViolated
config = ti_lib_ioc_port_configure_get(pin);
#else
config = ti_lib_rom_ioc_port_configure_get(pin);
#endif
config &= ~CONFIG_MASK;
tmp = cfg & GPIO_HAL_PIN_CFG_EDGE_BOTH;
@ -87,7 +82,7 @@ gpio_hal_arch_pin_cfg_set(gpio_hal_pin_t pin, gpio_hal_pin_cfg_t cfg)
config |= IOC_INT_ENABLE;
}
ti_lib_rom_ioc_port_configure_set(pin, IOC_PORT_GPIO, config);
ti_lib_ioc_port_configure_set(pin, IOC_PORT_GPIO, config);
}
/*---------------------------------------------------------------------------*/
gpio_hal_pin_cfg_t
@ -98,11 +93,7 @@ gpio_hal_arch_pin_cfg_get(gpio_hal_pin_t pin)
uint32_t config;
cfg = 0;
#ifdef ThisLibraryIsFor_CC26x0R2_HaltIfViolated
config = ti_lib_ioc_port_configure_get(pin);
#else
config = ti_lib_rom_ioc_port_configure_get(pin);
#endif
/* Pull */
tmp = config & IOC_IOPULL_M;

View File

@ -49,7 +49,6 @@
/*---------------------------------------------------------------------------*/
#include "contiki.h"
#include "ti-lib.h"
#include "ti-lib-rom.h"
#include <stdint.h>
/*---------------------------------------------------------------------------*/
@ -57,15 +56,10 @@
#define gpio_hal_arch_interrupt_enable(p) interrupt_enable(p)
#ifdef ThisLibraryIsFor_CC26x0R2_HaltIfViolated
#define gpio_hal_arch_interrupt_disable(p) ti_lib_ioc_int_disable(p)
#define gpio_hal_arch_pin_set_input(p) ti_lib_ioc_pin_type_gpio_input(p)
#define gpio_hal_arch_pin_set_output(p) ti_lib_ioc_pin_type_gpio_output(p)
#else
#define gpio_hal_arch_interrupt_disable(p) ti_lib_rom_ioc_int_disable(p)
#define gpio_hal_arch_pin_set_input(p) ti_lib_rom_ioc_pin_type_gpio_input(p)
#define gpio_hal_arch_pin_set_output(p) ti_lib_rom_ioc_pin_type_gpio_output(p)
#endif
#define gpio_hal_arch_set_pin(p) ti_lib_gpio_set_dio(p)
#define gpio_hal_arch_clear_pin(p) ti_lib_gpio_clear_dio(p)
#define gpio_hal_arch_toggle_pin(p) ti_lib_gpio_toggle_dio(p)
@ -80,11 +74,7 @@ static inline void
interrupt_enable(gpio_hal_pin_t pin)
{
ti_lib_gpio_clear_event_dio(pin);
#ifndef ThisLibraryIsFor_CC26x0R2_HaltIfViolated
ti_lib_rom_ioc_int_enable(pin);
#else
ti_lib_ioc_int_enable(pin);
#endif
}
/*---------------------------------------------------------------------------*/
#endif /* GPIO_HAL_ARCH_H_ */

View File

@ -99,7 +99,7 @@ soc_rtc_init(void)
ti_lib_aon_rtc_channel_enable(AON_RTC_CH1);
ti_lib_aon_rtc_enable();
ti_lib_rom_int_enable(INT_AON_RTC_COMB);
ti_lib_int_enable(INT_AON_RTC_COMB);
/* Re-enable interrupts */
if(!interrupts_disabled) {

View File

@ -71,7 +71,7 @@ static void
disable_number_ready_interrupt(void)
{
ti_lib_trng_int_disable(TRNG_NUMBER_READY);
ti_lib_rom_int_disable(INT_TRNG_IRQ);
ti_lib_int_disable(INT_TRNG_IRQ);
}
/*---------------------------------------------------------------------------*/
static void
@ -79,14 +79,14 @@ enable_number_ready_interrupt(void)
{
ti_lib_trng_int_clear(TRNG_NUMBER_READY);
ti_lib_trng_int_enable(TRNG_NUMBER_READY);
ti_lib_rom_int_enable(INT_TRNG_IRQ);
ti_lib_int_enable(INT_TRNG_IRQ);
}
/*---------------------------------------------------------------------------*/
static bool
accessible(void)
{
/* First, check the PD */
if(ti_lib_rom_prcm_power_domain_status(PRCM_DOMAIN_PERIPH)
if(ti_lib_prcm_power_domain_status(PRCM_DOMAIN_PERIPH)
!= PRCM_DOMAIN_POWER_ON) {
return false;
}
@ -104,12 +104,12 @@ static void
power_up(void)
{
/* First, make sure the PERIPH PD is on */
ti_lib_rom_prcm_power_domain_on(PRCM_DOMAIN_PERIPH);
while((ti_lib_rom_prcm_power_domain_status(PRCM_DOMAIN_PERIPH)
ti_lib_prcm_power_domain_on(PRCM_DOMAIN_PERIPH);
while((ti_lib_prcm_power_domain_status(PRCM_DOMAIN_PERIPH)
!= PRCM_DOMAIN_POWER_ON));
/* Enable clock in active mode */
ti_lib_rom_prcm_peripheral_run_enable(PRCM_PERIPH_TRNG);
ti_lib_prcm_peripheral_run_enable(PRCM_PERIPH_TRNG);
ti_lib_prcm_load_set();
while(!ti_lib_prcm_load_get());
}
@ -136,7 +136,7 @@ static uint64_t
read_number(void)
{
uint64_t ran = (uint64_t)HWREG(TRNG_BASE + TRNG_O_OUT1) << 32;
ran += ti_lib_rom_trng_number_get(TRNG_LOW_WORD);
ran += ti_lib_trng_number_get(TRNG_LOW_WORD);
return ran;
}
@ -237,7 +237,7 @@ soc_trng_rand_asynchronous(uint32_t samples, soc_trng_callback_t cb)
ti_lib_trng_int_clear(TRNG_NUMBER_READY);
/* Enable clock in sleep mode and register with LPM */
ti_lib_rom_prcm_peripheral_sleep_enable(PRCM_PERIPH_TRNG);
ti_lib_prcm_peripheral_sleep_enable(PRCM_PERIPH_TRNG);
ti_lib_prcm_load_set();
while(!ti_lib_prcm_load_get());
@ -271,7 +271,7 @@ PROCESS_THREAD(soc_trng_process, ev, data)
}
/* Disable clock in sleep mode */
ti_lib_rom_prcm_peripheral_sleep_disable(PRCM_PERIPH_TRNG);
ti_lib_prcm_peripheral_sleep_disable(PRCM_PERIPH_TRNG);
ti_lib_prcm_load_set();
while(!ti_lib_prcm_load_get());

View File

@ -123,7 +123,7 @@ spi_arch_lock_and_open(const spi_device_t *dev)
!= PRCM_DOMAIN_POWER_ON)) ;
/* Enable clock in active mode */
ti_lib_rom_prcm_peripheral_run_enable(spi_controller[dev->spi_controller].prcm_periph);
ti_lib_prcm_peripheral_run_enable(spi_controller[dev->spi_controller].prcm_periph);
ti_lib_prcm_load_set();
while(!ti_lib_prcm_load_get()) ;
@ -131,17 +131,14 @@ spi_arch_lock_and_open(const spi_device_t *dev)
ti_lib_ssi_int_disable(spi_controller[dev->spi_controller].ssi_base, SSI_RXOR | SSI_RXFF | SSI_RXTO | SSI_TXFF);
ti_lib_ssi_int_clear(spi_controller[dev->spi_controller].ssi_base, SSI_RXOR | SSI_RXTO);
#ifdef ThisLibraryIsFor_CC26x0R2_HaltIfViolated
ti_lib_ssi_config_set_exp_clk(spi_controller[dev->spi_controller].ssi_base, ti_lib_sys_ctrl_clock_get(),
get_mode(dev), SSI_MODE_MASTER, dev->spi_bit_rate, 8);
ti_lib_ioc_pin_type_ssi_master(spi_controller[dev->spi_controller].ssi_base, dev->pin_spi_miso,
dev->pin_spi_mosi, IOID_UNUSED, dev->pin_spi_sck);
#else
ti_lib_rom_ssi_config_set_exp_clk(spi_controller[dev->spi_controller].ssi_base, ti_lib_sys_ctrl_clock_get(),
get_mode(dev), SSI_MODE_MASTER, dev->spi_bit_rate, 8);
ti_lib_rom_ioc_pin_type_ssi_master(spi_controller[dev->spi_controller].ssi_base, dev->pin_spi_miso,
dev->pin_spi_mosi, IOID_UNUSED, dev->pin_spi_sck);
#endif
ti_lib_ssi_config_set_exp_clk(spi_controller[dev->spi_controller].ssi_base,
ti_lib_sys_ctrl_clock_get(),
get_mode(dev), SSI_MODE_MASTER,
dev->spi_bit_rate, 8);
ti_lib_ioc_pin_type_ssi_master(spi_controller[dev->spi_controller].ssi_base,
dev->pin_spi_miso,
dev->pin_spi_mosi, IOID_UNUSED,
dev->pin_spi_sck);
ti_lib_ssi_enable(spi_controller[dev->spi_controller].ssi_base);
@ -159,7 +156,7 @@ spi_arch_close_and_unlock(const spi_device_t *dev)
}
/* Power down SSI */
ti_lib_rom_prcm_peripheral_run_disable(spi_controller[dev->spi_controller].prcm_periph);
ti_lib_prcm_peripheral_run_disable(spi_controller[dev->spi_controller].prcm_periph);
ti_lib_prcm_load_set();
while(!ti_lib_prcm_load_get()) ;
@ -213,39 +210,12 @@ spi_arch_transfer(const spi_device_t *dev,
for(i = 0; i < totlen; i++) {
c = i < wlen ? write_buf[i] : 0;
ti_lib_ssi_data_put(spi_controller[dev->spi_controller].ssi_base, (uint8_t)c);
#ifdef ThisLibraryIsFor_CC26x0R2_HaltIfViolated
ti_lib_ssi_data_get(spi_controller[dev->spi_controller].ssi_base, &c);
#else
ti_lib_rom_ssi_data_get(spi_controller[dev->spi_controller].ssi_base, &c);
#endif
if(i < rlen) {
inbuf[i] = (uint8_t)c;
}
}
#ifdef ThisLibraryIsFor_CC26x0R2_HaltIfViolated
while(ti_lib_ssi_data_get_non_blocking(spi_controller[dev->spi_controller].ssi_base, &c)) ;
#else
while(ti_lib_rom_ssi_data_get_non_blocking(spi_controller[dev->spi_controller].ssi_base, &c)) ;
#endif
return SPI_DEV_STATUS_OK;
}
/*---------------------------------------------------------------------------*/
spi_status_t
spi_arch_select(const spi_device_t *dev)
{
if(!spi_arch_has_lock(dev)) {
return SPI_DEV_STATUS_BUS_NOT_OWNED;
}
ti_lib_gpio_clear_dio(dev->pin_spi_cs);
return SPI_DEV_STATUS_OK;
}
spi_status_t
spi_arch_deselect(const spi_device_t *dev)
{
ti_lib_gpio_set_dio(dev->pin_spi_cs);
return SPI_DEV_STATUS_OK;
}

View File

@ -162,10 +162,10 @@ lpm_shutdown(uint32_t wakeup_pin, uint32_t io_pull, uint32_t wake_on)
ti_lib_aon_wuc_mcu_power_off_config(MCU_VIRT_PWOFF_DISABLE);
/* Latch the IOs in the padring and enable I/O pad sleep mode */
#if !defined(ThisLibraryIsFor_CC26x0R2_HaltIfViolated)
ti_lib_pwr_ctrl_io_freeze_enable();
ti_lib_aon_ioc_freeze_enable();
HWREG(AON_SYSCTL_BASE + AON_SYSCTL_O_SLEEPCTL) = 0;
ti_lib_sys_ctrl_aon_sync();
#endif
/* Turn off VIMS cache, CRAM and TRAM - possibly not required */
ti_lib_prcm_cache_retention_disable();
ti_lib_vims_mode_set(VIMS_BASE, VIMS_MODE_OFF);
@ -193,12 +193,7 @@ wake_up(void)
ti_lib_sys_ctrl_aon_sync();
/* Adjust recharge settings */
#ifdef ThisLibraryIsFor_CC26x0R2_HaltIfViolated
// May need to change to XOSC_IN_LOW_POWER_MODE
ti_lib_sys_ctrl_adjust_recharge_after_power_down(XOSC_IN_HIGH_POWER_MODE);
#else
ti_lib_sys_ctrl_adjust_recharge_after_power_down();
#endif
/*
* Release the request to the uLDO

View File

@ -386,7 +386,7 @@ on(void)
rf_core_power_down();
return RF_CORE_CMD_ERROR;
}
rf_core_setup_interrupts(0);
rf_core_setup_interrupts();
oscillators_switch_to_hf_xosc();
if(rf_ble_cmd_setup_ble_mode() != RF_BLE_CMD_OK) {

View File

@ -0,0 +1,73 @@
/*
* Copyright (c) 2018, University of Bristol - http://www.bristol.ac.uk/
* 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 Institute 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 INSTITUTE 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 INSTITUTE 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.
*
* This file is part of the Contiki operating system.
*
*/
/**
* \file
* IEEE 802.15.4 TSCH timeslot timings for CC13xx chips at 50kbps datarate
* \author
* Atis Elsts <atis.elsts@bristol.ac.uk>
*
*/
#include "contiki.h"
#include "net/mac/tsch/tsch.h"
#define CC13XX_TSCH_DEFAULT_TS_CCA_OFFSET 1800
#define CC13XX_TSCH_DEFAULT_TS_CCA 128
#define CC13XX_TSCH_DEFAULT_TS_TX_OFFSET 2500
#define CC13XX_TSCH_DEFAULT_TS_RX_OFFSET (CC13XX_TSCH_DEFAULT_TS_TX_OFFSET - (TSCH_CONF_RX_WAIT / 2))
#define CC13XX_TSCH_DEFAULT_TS_RX_ACK_DELAY 2000
#define CC13XX_TSCH_DEFAULT_TS_TX_ACK_DELAY 3000
#define CC13XX_TSCH_DEFAULT_TS_RX_WAIT TSCH_CONF_RX_WAIT
#define CC13XX_TSCH_DEFAULT_TS_ACK_WAIT 3000
#define CC13XX_TSCH_DEFAULT_TS_RX_TX 192
#define CC13XX_TSCH_DEFAULT_TS_MAX_ACK 10000
#define CC13XX_TSCH_DEFAULT_TS_MAX_TX 21600
/* Timeslot length: 40000 usec */
#define CC13XX_TSCH_DEFAULT_TS_TIMESLOT_LENGTH 40000
/* TSCH timeslot timing (microseconds) */
const uint16_t tsch_timing_cc13xx_50kbps[tsch_ts_elements_count] = {
CC13XX_TSCH_DEFAULT_TS_CCA_OFFSET,
CC13XX_TSCH_DEFAULT_TS_CCA,
CC13XX_TSCH_DEFAULT_TS_TX_OFFSET,
CC13XX_TSCH_DEFAULT_TS_RX_OFFSET,
CC13XX_TSCH_DEFAULT_TS_RX_ACK_DELAY,
CC13XX_TSCH_DEFAULT_TS_TX_ACK_DELAY,
CC13XX_TSCH_DEFAULT_TS_RX_WAIT,
CC13XX_TSCH_DEFAULT_TS_ACK_WAIT,
CC13XX_TSCH_DEFAULT_TS_RX_TX,
CC13XX_TSCH_DEFAULT_TS_MAX_ACK,
CC13XX_TSCH_DEFAULT_TS_MAX_TX,
CC13XX_TSCH_DEFAULT_TS_TIMESLOT_LENGTH,
};

View File

@ -0,0 +1,41 @@
/*
* Copyright (c) 2018, University of Bristol - http://www.bristol.ac.uk/
* 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 Institute 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 INSTITUTE 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 INSTITUTE 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.
*
* This file is part of the Contiki operating system.
*
*/
#ifndef CC13XX_50KBPS_TSCH_H_
#define CC13XX_50KBPS_TSCH_H_
#include "contiki.h"
/* TSCH timeslot timing (microseconds) */
extern const uint16_t tsch_timing_cc13xx_50kbps[];
#endif /* CC13XX_50KBPS_TSCH_H_ */

View File

@ -120,6 +120,8 @@ static uint8_t rf_stats[16] = { 0 };
/* The size of the RF commands buffer */
#define RF_CMD_BUFFER_SIZE 128
/*---------------------------------------------------------------------------*/
#define RAT_TIMESTAMP_OFFSET_2_4_GHZ 0
/*---------------------------------------------------------------------------*/
/**
* \brief Returns the current status of a running Radio Op command
* \param a A pointer with the buffer used to initiate the command
@ -130,55 +132,9 @@ static uint8_t rf_stats[16] = { 0 };
*/
#define RF_RADIO_OP_GET_STATUS(a) (((rfc_radioOp_t *)a)->status)
/*---------------------------------------------------------------------------*/
/* Special value returned by CMD_IEEE_CCA_REQ when an RSSI is not available */
#define RF_CMD_CCA_REQ_RSSI_UNKNOWN -128
/* Used for the return value of channel_clear */
#define RF_CCA_CLEAR 1
#define RF_CCA_BUSY 0
/* Used as an error return value for get_cca_info */
#define RF_GET_CCA_INFO_ERROR 0xFF
/*
* Values of the individual bits of the ccaInfo field in CMD_IEEE_CCA_REQ's
* status struct
*/
#define RF_CMD_CCA_REQ_CCA_STATE_IDLE 0 /* 00 */
#define RF_CMD_CCA_REQ_CCA_STATE_BUSY 1 /* 01 */
#define RF_CMD_CCA_REQ_CCA_STATE_INVALID 2 /* 10 */
#define RF_CMD_CCA_REQ_CCA_CORR_IDLE (0 << 4)
#define RF_CMD_CCA_REQ_CCA_CORR_BUSY (1 << 4)
#define RF_CMD_CCA_REQ_CCA_CORR_INVALID (3 << 4)
#define RF_CMD_CCA_REQ_CCA_CORR_MASK (3 << 4)
#define RF_CMD_CCA_REQ_CCA_SYNC_BUSY (1 << 6)
/*---------------------------------------------------------------------------*/
#define IEEE_MODE_CHANNEL_MIN 11
#define IEEE_MODE_CHANNEL_MAX 26
/*---------------------------------------------------------------------------*/
/* How long to wait for an ongoing ACK TX to finish before starting frame TX */
#define TX_WAIT_TIMEOUT (RTIMER_SECOND >> 11)
/* How long to wait for the RF to enter RX in rf_cmd_ieee_rx */
#define ENTER_RX_WAIT_TIMEOUT (RTIMER_SECOND >> 10)
/* How long to wait for the RF to react on CMD_ABORT: around 1 msec */
#define RF_TURN_OFF_WAIT_TIMEOUT (RTIMER_SECOND >> 10)
/* How long to wait for the RF to finish TX of a packet or an ACK */
#define TX_FINISH_WAIT_TIMEOUT (RTIMER_SECOND >> 7)
#define LIMITED_BUSYWAIT(cond, timeout) do { \
rtimer_clock_t end_time = RTIMER_NOW() + timeout; \
while(cond) { \
if(!RTIMER_CLOCK_LT(RTIMER_NOW(), end_time)) { \
break; \
} \
} \
} while(0)
/*---------------------------------------------------------------------------*/
/* TX Power dBm lookup table - values from SmartRF Studio */
typedef struct output_config {
radio_value_t dbm;
@ -211,33 +167,6 @@ static const output_config_t output_power[] = {
/* Default TX Power - position in output_power[] */
static const output_config_t *tx_power_current = &output_power[0];
/*---------------------------------------------------------------------------*/
static volatile int8_t last_rssi = 0;
static volatile uint8_t last_corr_lqi = 0;
extern int32_t rat_offset;
/*---------------------------------------------------------------------------*/
/* SFD timestamp in RTIMER ticks */
static volatile uint32_t last_packet_timestamp = 0;
/* SFD timestamp in RAT ticks (but 64 bits) */
static uint64_t last_rat_timestamp64 = 0;
/* For RAT overflow handling */
static struct ctimer rat_overflow_timer;
static volatile uint32_t rat_overflow_counter = 0;
static rtimer_clock_t last_rat_overflow = 0;
/* RAT has 32-bit register, overflows once 18 minutes */
#define RAT_RANGE 4294967296ull
/* approximate value */
#define RAT_OVERFLOW_PERIOD_SECONDS (60 * 18)
/* XXX: don't know what exactly is this, looks like the time to Tx 3 octets */
#define TIMESTAMP_OFFSET -(USEC_TO_RADIO(32 * 3) - 1) /* -95.75 usec */
/*---------------------------------------------------------------------------*/
/* Are we currently in poll mode? */
static uint8_t poll_mode = 0;
static rfc_CMD_IEEE_MOD_FILT_t filter_cmd;
/*---------------------------------------------------------------------------*/
/*
@ -256,27 +185,28 @@ static uint8_t cmd_ieee_rx_buf[RF_CMD_BUFFER_SIZE] CC_ALIGN(4);
#define DATA_ENTRY_LENSZ_BYTE 1
#define DATA_ENTRY_LENSZ_WORD 2 /* 2 bytes */
#define RX_BUF_SIZE 144
/* Four receive buffers entries with room for 1 IEEE802.15.4 frame in each */
static uint8_t rx_buf_0[RX_BUF_SIZE] CC_ALIGN(4);
static uint8_t rx_buf_1[RX_BUF_SIZE] CC_ALIGN(4);
static uint8_t rx_buf_2[RX_BUF_SIZE] CC_ALIGN(4);
static uint8_t rx_buf_3[RX_BUF_SIZE] CC_ALIGN(4);
#define RX_BUF_INCLUDE_CRC 1
#define RX_BUF_INCLUDE_RSSI 1
#define RX_BUF_INCLUDE_CORR 1
#define RX_BUF_INCLUDE_TIMESTAMP 1
/* The size of the metadata (excluding the packet length field) */
#define RX_BUF_METADATA_SIZE \
(2 * RX_BUF_INCLUDE_CRC + RX_BUF_INCLUDE_RSSI + RX_BUF_INCLUDE_CORR + 4 * RX_BUF_INCLUDE_TIMESTAMP)
(2 * RF_CORE_RX_BUF_INCLUDE_CRC \
+ RF_CORE_RX_BUF_INCLUDE_RSSI \
+ RF_CORE_RX_BUF_INCLUDE_CORR \
+ 4 * RF_CORE_RX_BUF_INCLUDE_TIMESTAMP)
/* The offset of the packet length in a rx buffer */
#define RX_BUF_LENGTH_OFFSET sizeof(rfc_dataEntry_t)
/* The offset of the packet data in a rx buffer */
#define RX_BUF_DATA_OFFSET (RX_BUF_LENGTH_OFFSET + 1)
#define RX_BUF_SIZE (RX_BUF_DATA_OFFSET \
+ NETSTACK_RADIO_MAX_PAYLOAD_LEN \
+ RX_BUF_METADATA_SIZE)
/* Four receive buffers entries with room for 1 IEEE802.15.4 frame in each */
static uint8_t rx_buf_0[RX_BUF_SIZE] CC_ALIGN(4);
static uint8_t rx_buf_1[RX_BUF_SIZE] CC_ALIGN(4);
static uint8_t rx_buf_2[RX_BUF_SIZE] CC_ALIGN(4);
static uint8_t rx_buf_3[RX_BUF_SIZE] CC_ALIGN(4);
/* The RX Data Queue */
static dataQueue_t rx_data_queue = { 0 };
@ -358,8 +288,8 @@ transmitting(void)
return 0;
}
if((cmd.currentRssi == RF_CMD_CCA_REQ_RSSI_UNKNOWN) &&
(cmd.ccaInfo.ccaEnergy == RF_CMD_CCA_REQ_CCA_STATE_BUSY)) {
if((cmd.currentRssi == RF_CORE_CMD_CCA_REQ_RSSI_UNKNOWN) &&
(cmd.ccaInfo.ccaEnergy == RF_CORE_CMD_CCA_REQ_CCA_STATE_BUSY)) {
return 1;
}
@ -368,12 +298,12 @@ transmitting(void)
/*---------------------------------------------------------------------------*/
/**
* \brief Returns CCA information
* \return RF_GET_CCA_INFO_ERROR if the RF was not on
* \return RF_CORE_GET_CCA_INFO_ERROR if the RF was not on
* \return On success, the return value is formatted as per the ccaInfo field
* of CMD_IEEE_CCA_REQ
*
* It is the caller's responsibility to make sure the RF is on. This function
* will return RF_GET_CCA_INFO_ERROR if the RF is off
* will return RF_CORE_GET_CCA_INFO_ERROR if the RF is off
*
* This function will in fact wait for a valid CCA state
*/
@ -385,20 +315,20 @@ get_cca_info(void)
if(!rf_is_on()) {
PRINTF("get_cca_info: Not on\n");
return RF_GET_CCA_INFO_ERROR;
return RF_CORE_GET_CCA_INFO_ERROR;
}
memset(&cmd, 0x00, sizeof(cmd));
cmd.ccaInfo.ccaState = RF_CMD_CCA_REQ_CCA_STATE_INVALID;
cmd.ccaInfo.ccaState = RF_CORE_CMD_CCA_REQ_CCA_STATE_INVALID;
while(cmd.ccaInfo.ccaState == RF_CMD_CCA_REQ_CCA_STATE_INVALID) {
while(cmd.ccaInfo.ccaState == RF_CORE_CMD_CCA_REQ_CCA_STATE_INVALID) {
memset(&cmd, 0x00, sizeof(cmd));
cmd.commandNo = CMD_IEEE_CCA_REQ;
if(rf_core_send_cmd((uint32_t)&cmd, &cmd_status) == RF_CORE_CMD_ERROR) {
PRINTF("get_cca_info: CMDSTA=0x%08lx\n", cmd_status);
return RF_GET_CCA_INFO_ERROR;
return RF_CORE_GET_CCA_INFO_ERROR;
}
}
@ -425,14 +355,14 @@ get_rssi(void)
was_off = 1;
if(on() != RF_CORE_CMD_OK) {
PRINTF("get_rssi: on() failed\n");
return RF_CMD_CCA_REQ_RSSI_UNKNOWN;
return RF_CORE_CMD_CCA_REQ_RSSI_UNKNOWN;
}
}
memset(&cmd, 0x00, sizeof(cmd));
cmd.ccaInfo.ccaEnergy = RF_CMD_CCA_REQ_CCA_STATE_INVALID;
cmd.ccaInfo.ccaEnergy = RF_CORE_CMD_CCA_REQ_CCA_STATE_INVALID;
while(cmd.ccaInfo.ccaEnergy == RF_CMD_CCA_REQ_CCA_STATE_INVALID) {
while(cmd.ccaInfo.ccaEnergy == RF_CORE_CMD_CCA_REQ_CCA_STATE_INVALID) {
memset(&cmd, 0x00, sizeof(cmd));
cmd.commandNo = CMD_IEEE_CCA_REQ;
@ -440,7 +370,7 @@ get_rssi(void)
PRINTF("get_rssi: CMDSTA=0x%08lx\n", cmd_status);
/* Make sure to return RSSI unknown */
cmd.currentRssi = RF_CMD_CCA_REQ_RSSI_UNKNOWN;
cmd.currentRssi = RF_CORE_CMD_CCA_REQ_RSSI_UNKNOWN;
break;
}
}
@ -558,8 +488,8 @@ rf_cmd_ieee_rx()
return RF_CORE_CMD_ERROR;
}
LIMITED_BUSYWAIT(RF_RADIO_OP_GET_STATUS(cmd_ieee_rx_buf) != RF_CORE_RADIO_OP_STATUS_ACTIVE,
ENTER_RX_WAIT_TIMEOUT);
RTIMER_BUSYWAIT_UNTIL(RF_RADIO_OP_GET_STATUS(cmd_ieee_rx_buf) == RF_CORE_RADIO_OP_STATUS_ACTIVE,
RF_CORE_ENTER_RX_TIMEOUT);
/* Wait to enter RX */
if(RF_RADIO_OP_GET_STATUS(cmd_ieee_rx_buf) != RF_CORE_RADIO_OP_STATUS_ACTIVE) {
@ -615,11 +545,11 @@ init_rf_params(void)
cmd->rxConfig.bAutoFlushCrc = 1;
cmd->rxConfig.bAutoFlushIgn = 0;
cmd->rxConfig.bIncludePhyHdr = 0;
cmd->rxConfig.bIncludeCrc = RX_BUF_INCLUDE_CRC;
cmd->rxConfig.bAppendRssi = RX_BUF_INCLUDE_RSSI;
cmd->rxConfig.bAppendCorrCrc = RX_BUF_INCLUDE_CORR;
cmd->rxConfig.bIncludeCrc = RF_CORE_RX_BUF_INCLUDE_CRC;
cmd->rxConfig.bAppendRssi = RF_CORE_RX_BUF_INCLUDE_RSSI;
cmd->rxConfig.bAppendCorrCrc = RF_CORE_RX_BUF_INCLUDE_CORR;
cmd->rxConfig.bAppendSrcInd = 0;
cmd->rxConfig.bAppendTimestamp = RX_BUF_INCLUDE_TIMESTAMP;
cmd->rxConfig.bAppendTimestamp = RF_CORE_RX_BUF_INCLUDE_TIMESTAMP;
cmd->pRxQ = &rx_data_queue;
cmd->pOutput = (rfc_ieeeRxOutput_t *)rf_stats;
@ -714,7 +644,7 @@ rx_off(void)
}
/* Wait for ongoing ACK TX to finish */
LIMITED_BUSYWAIT(transmitting(), TX_FINISH_WAIT_TIMEOUT);
RTIMER_BUSYWAIT_UNTIL(!transmitting(), RF_CORE_TX_FINISH_TIMEOUT);
/* Send a CMD_ABORT command to RF Core */
if(rf_core_send_cmd(CMDR_DIR_CMD(CMD_ABORT), &cmd_status) != RF_CORE_CMD_OK) {
@ -722,7 +652,7 @@ rx_off(void)
/* Continue nonetheless */
}
LIMITED_BUSYWAIT(rf_is_on(), RF_TURN_OFF_WAIT_TIMEOUT);
RTIMER_BUSYWAIT_UNTIL(!rf_is_on(), RF_CORE_TURN_OFF_TIMEOUT);
if(RF_RADIO_OP_GET_STATUS(cmd_ieee_rx_buf) == IEEE_DONE_STOPPED ||
RF_RADIO_OP_GET_STATUS(cmd_ieee_rx_buf) == IEEE_DONE_ABORT) {
@ -773,8 +703,8 @@ soft_off(void)
return;
}
LIMITED_BUSYWAIT((cmd->status & RF_CORE_RADIO_OP_MASKED_STATUS) ==
RF_CORE_RADIO_OP_MASKED_STATUS_RUNNING, RF_TURN_OFF_WAIT_TIMEOUT);
RTIMER_BUSYWAIT_UNTIL((cmd->status & RF_CORE_RADIO_OP_MASKED_STATUS) !=
RF_CORE_RADIO_OP_MASKED_STATUS_RUNNING, RF_CORE_TURN_OFF_TIMEOUT);
}
/*---------------------------------------------------------------------------*/
static uint8_t
@ -791,71 +721,10 @@ soft_on(void)
static const rf_core_primary_mode_t mode_ieee = {
soft_off,
soft_on,
rf_is_on,
RAT_TIMESTAMP_OFFSET_2_4_GHZ
};
/*---------------------------------------------------------------------------*/
static uint8_t
check_rat_overflow(bool first_time)
{
static uint32_t last_value;
uint32_t current_value;
uint8_t interrupts_disabled;
/* Bail out if the RF is not on */
if(!rf_is_on()) {
return 0;
}
interrupts_disabled = ti_lib_int_master_disable();
if(first_time) {
last_value = HWREG(RFC_RAT_BASE + RATCNT);
} else {
current_value = HWREG(RFC_RAT_BASE + RATCNT);
if(current_value + RAT_RANGE / 4 < last_value) {
/* Overflow detected */
last_rat_overflow = RTIMER_NOW();
rat_overflow_counter++;
}
last_value = current_value;
}
if(!interrupts_disabled) {
ti_lib_int_master_enable();
}
return 1;
}
/*---------------------------------------------------------------------------*/
static void
handle_rat_overflow(void *unused)
{
uint8_t success;
uint8_t was_off = 0;
if(!rf_is_on()) {
was_off = 1;
if(on() != RF_CORE_CMD_OK) {
PRINTF("overflow: on() failed\n");
ctimer_set(&rat_overflow_timer, CLOCK_SECOND,
handle_rat_overflow, NULL);
return;
}
}
success = check_rat_overflow(false);
if(was_off) {
off();
}
if(success) {
/* Retry after half of the interval */
ctimer_set(&rat_overflow_timer, RAT_OVERFLOW_PERIOD_SECONDS * CLOCK_SECOND / 2,
handle_rat_overflow, NULL);
} else {
/* Retry sooner */
ctimer_set(&rat_overflow_timer, CLOCK_SECOND,
handle_rat_overflow, NULL);
}
}
/*---------------------------------------------------------------------------*/
static int
init(void)
{
@ -889,9 +758,7 @@ init(void)
rf_core_primary_mode_register(&mode_ieee);
check_rat_overflow(true);
ctimer_set(&rat_overflow_timer, RAT_OVERFLOW_PERIOD_SECONDS * CLOCK_SECOND / 2,
handle_rat_overflow, NULL);
rf_core_rat_init();
process_start(&rf_core_process, NULL);
return 1;
@ -935,7 +802,7 @@ transmit(unsigned short transmit_len)
do {
tx_active = transmitting();
} while(tx_active == 1 &&
(RTIMER_CLOCK_LT(RTIMER_NOW(), t0 + TX_WAIT_TIMEOUT)));
(RTIMER_CLOCK_LT(RTIMER_NOW(), t0 + RF_CORE_TX_TIMEOUT)));
if(tx_active) {
PRINTF("transmit: Already TXing and wait timed out\n");
@ -957,7 +824,7 @@ transmit(unsigned short transmit_len)
cmd.startTrigger.triggerType = TRIG_NOW;
/* Enable the LAST_FG_COMMAND_DONE interrupt, which will wake us up */
rf_core_cmd_done_en(true, poll_mode);
rf_core_cmd_done_en(true);
ret = rf_core_send_cmd((uint32_t)&cmd, &cmd_status);
@ -973,7 +840,7 @@ transmit(unsigned short transmit_len)
* 1) make the `lpm_sleep()` call here unconditional;
* 2) change the radio ISR priority to allow radio ISR to interrupt rtimer ISR.
*/
if(!poll_mode) {
if(!rf_core_poll_mode) {
lpm_sleep();
}
}
@ -1007,7 +874,7 @@ transmit(unsigned short transmit_len)
* Disable LAST_FG_COMMAND_DONE interrupt. We don't really care about it
* except when we are transmitting
*/
rf_core_cmd_done_dis(poll_mode);
rf_core_cmd_done_dis();
if(was_off) {
off();
@ -1036,46 +903,6 @@ release_data_entry(void)
rx_read_entry = entry->pNextEntry;
}
/*---------------------------------------------------------------------------*/
static uint32_t
calc_last_packet_timestamp(uint32_t rat_timestamp)
{
uint64_t rat_timestamp64;
uint32_t adjusted_overflow_counter;
uint8_t was_off = 0;
if(!rf_is_on()) {
was_off = 1;
on();
}
if(rf_is_on()) {
check_rat_overflow(false);
if(was_off) {
off();
}
}
adjusted_overflow_counter = rat_overflow_counter;
/* if the timestamp is large and the last oveflow was recently,
assume that the timestamp refers to the time before the overflow */
if(rat_timestamp > (uint32_t)(RAT_RANGE * 3 / 4)) {
if(RTIMER_CLOCK_LT(RTIMER_NOW(),
last_rat_overflow + RAT_OVERFLOW_PERIOD_SECONDS * RTIMER_SECOND / 4)) {
adjusted_overflow_counter--;
}
}
/* add the overflowed time to the timestamp */
rat_timestamp64 = rat_timestamp + RAT_RANGE * adjusted_overflow_counter;
/* correct timestamp so that it refers to the end of the SFD */
rat_timestamp64 += TIMESTAMP_OFFSET;
last_rat_timestamp64 = rat_timestamp64 - rat_offset;
return RADIO_TO_RTIMER(rat_timestamp64 - rat_offset);
}
/*---------------------------------------------------------------------------*/
static int
read_frame(void *buf, unsigned short buf_len)
{
@ -1111,20 +938,20 @@ read_frame(void *buf, unsigned short buf_len)
memcpy(buf, (uint8_t *)rx_read_entry + RX_BUF_DATA_OFFSET, len);
last_rssi = (int8_t)rx_read_entry[RX_BUF_DATA_OFFSET + len + 2];
last_corr_lqi = (uint8_t)rx_read_entry[RX_BUF_DATA_OFFSET + len + 3] & STATUS_CORRELATION;
rf_core_last_rssi = (int8_t)rx_read_entry[RX_BUF_DATA_OFFSET + len];
rf_core_last_corr_lqi = (uint8_t)rx_read_entry[RX_BUF_DATA_OFFSET + len + 1] & STATUS_CORRELATION;
/* get the timestamp */
memcpy(&rat_timestamp, (uint8_t *)rx_read_entry + RX_BUF_DATA_OFFSET + len + 4, 4);
memcpy(&rat_timestamp, (uint8_t *)rx_read_entry + RX_BUF_DATA_OFFSET + len + 2, 4);
last_packet_timestamp = calc_last_packet_timestamp(rat_timestamp);
rf_core_last_packet_timestamp = rf_core_convert_rat_to_rtimer(rat_timestamp);
if(!poll_mode) {
if(!rf_core_poll_mode) {
/* Not in poll mode: packetbuf should not be accessed in interrupt context.
* In poll mode, the last packet RSSI and link quality can be obtained through
* RADIO_PARAM_LAST_RSSI and RADIO_PARAM_LAST_LINK_QUALITY */
packetbuf_set_attr(PACKETBUF_ATTR_RSSI, last_rssi);
packetbuf_set_attr(PACKETBUF_ATTR_LINK_QUALITY, last_corr_lqi);
packetbuf_set_attr(PACKETBUF_ATTR_RSSI, rf_core_last_rssi);
packetbuf_set_attr(PACKETBUF_ATTR_LINK_QUALITY, rf_core_last_corr_lqi);
}
release_data_entry();
@ -1137,7 +964,7 @@ channel_clear(void)
{
uint8_t was_off = 0;
uint8_t cca_info;
int ret = RF_CCA_CLEAR;
int ret = RF_CORE_CCA_CLEAR;
/*
* If we are in the middle of a BLE operation, we got called by ContikiMAC
@ -1145,7 +972,7 @@ channel_clear(void)
*/
if(rf_ble_is_active() == RF_BLE_ACTIVE) {
PRINTF("channel_clear: Interrupt context but BLE in progress\n");
return RF_CCA_CLEAR;
return RF_CORE_CCA_CLEAR;
}
if(rf_is_on()) {
@ -1157,7 +984,7 @@ channel_clear(void)
*
* We could probably even simply return that the channel is clear
*/
LIMITED_BUSYWAIT(transmitting(), TX_FINISH_WAIT_TIMEOUT);
RTIMER_BUSYWAIT_UNTIL(!transmitting(), RF_CORE_TX_FINISH_TIMEOUT);
} else {
was_off = 1;
if(on() != RF_CORE_CMD_OK) {
@ -1165,21 +992,21 @@ channel_clear(void)
if(was_off) {
off();
}
return RF_CCA_CLEAR;
return RF_CORE_CCA_CLEAR;
}
}
cca_info = get_cca_info();
if(cca_info == RF_GET_CCA_INFO_ERROR) {
if(cca_info == RF_CORE_GET_CCA_INFO_ERROR) {
PRINTF("channel_clear: CCA error\n");
ret = RF_CCA_CLEAR;
ret = RF_CORE_CCA_CLEAR;
} else {
/*
* cca_info bits 1:0 - ccaStatus
* Return 1 (clear) if idle or invalid.
*/
ret = (cca_info & 0x03) != RF_CMD_CCA_REQ_CCA_STATE_BUSY;
ret = (cca_info & 0x03) != RF_CORE_CMD_CCA_REQ_CCA_STATE_BUSY;
}
if(was_off) {
@ -1218,12 +1045,12 @@ receiving_packet(void)
cca_info = get_cca_info();
/* If we can't read CCA info, return "not receiving" */
if(cca_info == RF_GET_CCA_INFO_ERROR) {
if(cca_info == RF_CORE_GET_CCA_INFO_ERROR) {
return 0;
}
/* If sync has been seen, return 1 (receiving) */
if(cca_info & RF_CMD_CCA_REQ_CCA_SYNC_BUSY) {
if(cca_info & RF_CORE_CMD_CCA_REQ_CCA_SYNC_BUSY) {
return 1;
}
@ -1241,7 +1068,7 @@ pending_packet(void)
if(entry->status == DATA_ENTRY_STATUS_FINISHED
|| entry->status == DATA_ENTRY_STATUS_BUSY) {
rv = 1;
if(!poll_mode) {
if(!rf_core_poll_mode) {
process_poll(&rf_core_process);
}
}
@ -1292,7 +1119,7 @@ on(void)
return RF_CORE_CMD_ERROR;
}
rf_core_setup_interrupts(poll_mode);
rf_core_setup_interrupts();
if(rf_radio_setup() != RF_CORE_CMD_OK) {
PRINTF("on: radio_setup() failed\n");
@ -1314,7 +1141,7 @@ off(void)
return RF_CORE_CMD_OK;
}
LIMITED_BUSYWAIT(transmitting(), TX_FINISH_WAIT_TIMEOUT);
RTIMER_BUSYWAIT_UNTIL(!transmitting(), RF_CORE_TX_FINISH_TIMEOUT);
/* stopping the rx explicitly results in lower sleep-mode power usage */
rx_off();
@ -1394,7 +1221,7 @@ get_value(radio_param_t param, radio_value_t *value)
if(cmd->frameFiltOpt.autoAckEn) {
*value |= RADIO_RX_MODE_AUTOACK;
}
if(poll_mode) {
if(rf_core_poll_mode) {
*value |= RADIO_RX_MODE_POLL_MODE;
}
@ -1411,7 +1238,7 @@ get_value(radio_param_t param, radio_value_t *value)
case RADIO_PARAM_RSSI:
*value = get_rssi();
if(*value == RF_CMD_CCA_REQ_RSSI_UNKNOWN) {
if(*value == RF_CORE_CMD_CCA_REQ_RSSI_UNKNOWN) {
return RADIO_RESULT_ERROR;
} else {
return RADIO_RESULT_OK;
@ -1429,10 +1256,25 @@ get_value(radio_param_t param, radio_value_t *value)
*value = OUTPUT_POWER_MAX;
return RADIO_RESULT_OK;
case RADIO_PARAM_LAST_RSSI:
*value = last_rssi;
*value = rf_core_last_rssi;
return RADIO_RESULT_OK;
case RADIO_PARAM_LAST_LINK_QUALITY:
*value = last_corr_lqi;
*value = rf_core_last_corr_lqi;
return RADIO_RESULT_OK;
case RADIO_CONST_PHY_OVERHEAD:
*value = (radio_value_t)RADIO_PHY_OVERHEAD;
return RADIO_RESULT_OK;
case RADIO_CONST_BYTE_AIR_TIME:
*value = (radio_value_t)RADIO_BYTE_AIR_TIME;
return RADIO_RESULT_OK;
case RADIO_CONST_DELAY_BEFORE_TX:
*value = (radio_value_t)RADIO_DELAY_BEFORE_TX;
return RADIO_RESULT_OK;
case RADIO_CONST_DELAY_BEFORE_RX:
*value = (radio_value_t)RADIO_DELAY_BEFORE_RX;
return RADIO_RESULT_OK;
case RADIO_CONST_DELAY_BEFORE_DETECT:
*value = (radio_value_t)RADIO_DELAY_BEFORE_DETECT;
return RADIO_RESULT_OK;
default:
return RADIO_RESULT_NOT_SUPPORTED;
@ -1498,9 +1340,9 @@ set_value(radio_param_t param, radio_value_t value)
cmd->frameFiltOpt.bPanCoord = 0;
cmd->frameFiltOpt.bStrictLenFilter = 0;
old_poll_mode = poll_mode;
poll_mode = (value & RADIO_RX_MODE_POLL_MODE) != 0;
if(poll_mode == old_poll_mode) {
old_poll_mode = rf_core_poll_mode;
rf_core_poll_mode = (value & RADIO_RX_MODE_POLL_MODE) != 0;
if(rf_core_poll_mode == old_poll_mode) {
uint32_t cmd_status;
/* do not turn the radio on and off, just send an update command */
@ -1552,7 +1394,7 @@ set_value(radio_param_t param, radio_value_t value)
/* Restart the radio timer (RAT).
This causes resynchronization between RAT and RTC: useful for TSCH. */
if(rf_core_restart_rat() == RF_CORE_CMD_OK) {
check_rat_overflow(false);
rf_core_check_rat_overflow();
}
if(rx_on() != RF_CORE_CMD_OK) {
@ -1590,7 +1432,7 @@ get_object(radio_param_t param, void *dest, size_t size)
if(size != sizeof(rtimer_clock_t) || !dest) {
return RADIO_RESULT_INVALID_VALUE;
}
*(rtimer_clock_t *)dest = last_packet_timestamp;
*(rtimer_clock_t *)dest = rf_core_last_packet_timestamp;
return RADIO_RESULT_OK;
}

View File

@ -115,24 +115,6 @@
*/
#define RF_RADIO_OP_GET_STATUS(a) GET_FIELD_V(a, radioOp, status)
/*---------------------------------------------------------------------------*/
/* Special value returned by CMD_IEEE_CCA_REQ when an RSSI is not available */
#define RF_CMD_CCA_REQ_RSSI_UNKNOWN -128
/* Used for the return value of channel_clear */
#define RF_CCA_CLEAR 1
#define RF_CCA_BUSY 0
/* Used as an error return value for get_cca_info */
#define RF_GET_CCA_INFO_ERROR 0xFF
/*
* Values of the individual bits of the ccaInfo field in CMD_IEEE_CCA_REQ's
* status struct
*/
#define RF_CMD_CCA_REQ_CCA_STATE_IDLE 0 /* 00 */
#define RF_CMD_CCA_REQ_CCA_STATE_BUSY 1 /* 01 */
#define RF_CMD_CCA_REQ_CCA_STATE_INVALID 2 /* 10 */
#ifdef PROP_MODE_CONF_RSSI_THRESHOLD
#define PROP_MODE_RSSI_THRESHOLD PROP_MODE_CONF_RSSI_THRESHOLD
#else
@ -141,6 +123,8 @@
static int8_t rssi_threshold = PROP_MODE_RSSI_THRESHOLD;
/*---------------------------------------------------------------------------*/
static volatile uint8_t is_receiving_packet;
/*---------------------------------------------------------------------------*/
static int on(void);
static int off(void);
@ -170,12 +154,6 @@ static rfc_propRxOutput_t rx_stats;
#define DOT_4G_PHR_DW_BIT 0
#endif
/*---------------------------------------------------------------------------*/
/* How long to wait for an ongoing ACK TX to finish before starting frame TX */
#define TX_WAIT_TIMEOUT (RTIMER_SECOND >> 11)
/* How long to wait for the RF to enter RX in rf_cmd_ieee_rx */
#define ENTER_RX_WAIT_TIMEOUT (RTIMER_SECOND >> 10)
/*---------------------------------------------------------------------------*/
/* TX power table for the 431-527MHz band */
#ifdef PROP_MODE_CONF_TX_POWER_431_527
#define PROP_MODE_TX_POWER_431_527 PROP_MODE_CONF_TX_POWER_431_527
@ -222,12 +200,29 @@ static const prop_mode_tx_power_config_t *tx_power_current = &TX_POWER_DRIVER[1]
#define DATA_ENTRY_LENSZ_BYTE 1
#define DATA_ENTRY_LENSZ_WORD 2 /* 2 bytes */
/* The size of the metadata (excluding the packet length field) */
#define RX_BUF_METADATA_SIZE \
(CRC_LEN * RF_CORE_RX_BUF_INCLUDE_CRC \
+ RF_CORE_RX_BUF_INCLUDE_RSSI \
+ RF_CORE_RX_BUF_INCLUDE_CORR \
+ 4 * RF_CORE_RX_BUF_INCLUDE_TIMESTAMP)
/* The offset of the packet length in a rx buffer */
#define RX_BUF_LENGTH_OFFSET sizeof(rfc_dataEntry_t)
/* The offset of the packet data in a rx buffer */
#define RX_BUF_DATA_OFFSET (RX_BUF_LENGTH_OFFSET + DOT_4G_PHR_LEN)
#define ALIGN_TO_4(size) (((size) + 3) & ~3)
#define RX_BUF_SIZE ALIGN_TO_4(RX_BUF_DATA_OFFSET \
+ NETSTACK_RADIO_MAX_PAYLOAD_LEN \
+ RX_BUF_METADATA_SIZE)
/*
* RX buffers.
* PROP_MODE_RX_BUF_CNT buffers of RX_BUF_SIZE bytes each. The start of each
* buffer must be 4-byte aligned, therefore RX_BUF_SIZE must divide by 4
*/
#define RX_BUF_SIZE 140
static uint8_t rx_buf[PROP_MODE_RX_BUF_CNT][RX_BUF_SIZE] CC_ALIGN(4);
/* The RX Data Queue */
@ -236,6 +231,12 @@ static dataQueue_t rx_data_queue = { 0 };
/* Receive entry pointer to keep track of read items */
volatile static uint8_t *rx_read_entry;
/*---------------------------------------------------------------------------*/
/*
* Increasing this number causes unicast Tx immediately after broadcast Rx to have
* negative synchronization errors ("dr" in TSCH logs); decreasing it: the opposite.
*/
#define RAT_TIMESTAMP_OFFSET_SUB_GHZ USEC_TO_RADIO(160 * 6 - 240)
/*---------------------------------------------------------------------------*/
/* The outgoing frame buffer */
#define TX_BUF_PAYLOAD_LEN 180
#define TX_BUF_HDR_LEN 2
@ -272,13 +273,13 @@ get_rssi(void)
was_off = 1;
if(on() != RF_CORE_CMD_OK) {
PRINTF("get_rssi: on() failed\n");
return RF_CMD_CCA_REQ_RSSI_UNKNOWN;
return RF_CORE_CMD_CCA_REQ_RSSI_UNKNOWN;
}
}
rssi = RF_CMD_CCA_REQ_RSSI_UNKNOWN;
rssi = RF_CORE_CMD_CCA_REQ_RSSI_UNKNOWN;
while((rssi == RF_CMD_CCA_REQ_RSSI_UNKNOWN || rssi == 0) && ++attempts < 10) {
while((rssi == RF_CORE_CMD_CCA_REQ_RSSI_UNKNOWN || rssi == 0) && ++attempts < 10) {
memset(&cmd, 0x00, sizeof(cmd));
cmd.commandNo = CMD_GET_RSSI;
@ -420,13 +421,17 @@ static uint8_t
rf_cmd_prop_rx()
{
uint32_t cmd_status;
rtimer_clock_t t0;
volatile rfc_CMD_PROP_RX_ADV_t *cmd_rx_adv;
int ret;
cmd_rx_adv = (rfc_CMD_PROP_RX_ADV_t *)&smartrf_settings_cmd_prop_rx_adv;
cmd_rx_adv->status = RF_CORE_RADIO_OP_STATUS_IDLE;
cmd_rx_adv->rxConf.bIncludeCrc = RF_CORE_RX_BUF_INCLUDE_CRC;
cmd_rx_adv->rxConf.bAppendRssi = RF_CORE_RX_BUF_INCLUDE_RSSI;
cmd_rx_adv->rxConf.bAppendTimestamp = RF_CORE_RX_BUF_INCLUDE_TIMESTAMP;
cmd_rx_adv->rxConf.bAppendStatus = RF_CORE_RX_BUF_INCLUDE_CORR;
/*
* Set the max Packet length. This is for the payload only, therefore
* 2047 - length offset
@ -441,10 +446,8 @@ rf_cmd_prop_rx()
return RF_CORE_CMD_ERROR;
}
t0 = RTIMER_NOW();
while(cmd_rx_adv->status != RF_CORE_RADIO_OP_STATUS_ACTIVE &&
(RTIMER_CLOCK_LT(RTIMER_NOW(), t0 + ENTER_RX_WAIT_TIMEOUT)));
RTIMER_BUSYWAIT_UNTIL(cmd_rx_adv->status == RF_CORE_RADIO_OP_STATUS_ACTIVE,
RF_CORE_ENTER_RX_TIMEOUT);
/* Wait to enter RX */
if(cmd_rx_adv->status != RF_CORE_RADIO_OP_STATUS_ACTIVE) {
@ -506,13 +509,16 @@ rx_off_prop(void)
return RF_CORE_CMD_OK;
}
/* Wait for ongoing ACK TX to finish */
RTIMER_BUSYWAIT_UNTIL(!transmitting(), RF_CORE_TX_FINISH_TIMEOUT);
/* Send a CMD_ABORT command to RF Core */
if(rf_core_send_cmd(CMDR_DIR_CMD(CMD_ABORT), &cmd_status) != RF_CORE_CMD_OK) {
PRINTF("rx_off_prop: CMD_ABORT status=0x%08lx\n", cmd_status);
/* Continue nonetheless */
}
while(rf_is_on());
RTIMER_BUSYWAIT_UNTIL(!rf_is_on(), RF_CORE_TURN_OFF_TIMEOUT);
if(smartrf_settings_cmd_prop_rx_adv.status == PROP_DONE_STOPPED ||
smartrf_settings_cmd_prop_rx_adv.status == PROP_DONE_ABORT) {
@ -583,8 +589,8 @@ soft_off_prop(void)
return;
}
while((cmd->status & RF_CORE_RADIO_OP_MASKED_STATUS) ==
RF_CORE_RADIO_OP_MASKED_STATUS_RUNNING);
RTIMER_BUSYWAIT_UNTIL((cmd->status & RF_CORE_RADIO_OP_MASKED_STATUS) !=
RF_CORE_RADIO_OP_MASKED_STATUS_RUNNING, RF_CORE_TURN_OFF_TIMEOUT);
}
/*---------------------------------------------------------------------------*/
static uint8_t
@ -606,6 +612,8 @@ soft_on_prop(void)
static const rf_core_primary_mode_t mode_prop = {
soft_off_prop,
soft_on_prop,
rf_is_on,
RAT_TIMESTAMP_OFFSET_SUB_GHZ
};
/*---------------------------------------------------------------------------*/
static int
@ -637,10 +645,15 @@ init(void)
return RF_CORE_CMD_ERROR;
}
/* Enable the "sync word seen" interrupt */
ti_lib_rfc_hw_int_enable(RFC_DBELL_RFHWIEN_MDMSOFT);
ENERGEST_ON(ENERGEST_TYPE_LISTEN);
rf_core_primary_mode_register(&mode_prop);
rf_core_rat_init();
process_start(&rf_core_process, NULL);
return 1;
@ -701,7 +714,7 @@ transmit(unsigned short transmit_len)
rx_off_prop();
/* Enable the LAST_COMMAND_DONE interrupt to wake us up */
rf_core_cmd_done_en(false, false);
rf_core_cmd_done_en(false);
ret = rf_core_send_cmd((uint32_t)cmd_tx_adv, &cmd_status);
@ -714,7 +727,14 @@ transmit(unsigned short transmit_len)
/* Idle away while the command is running */
while((cmd_tx_adv->status & RF_CORE_RADIO_OP_MASKED_STATUS)
== RF_CORE_RADIO_OP_MASKED_STATUS_RUNNING) {
lpm_sleep();
/* Note: for now sleeping while Tx'ing in polling mode is disabled.
* To enable it:
* 1) make the `lpm_sleep()` call here unconditional;
* 2) change the radio ISR priority to allow radio ISR to interrupt rtimer ISR.
*/
if(!rf_core_poll_mode) {
lpm_sleep();
}
}
if(cmd_tx_adv->status == RF_CORE_RADIO_OP_STATUS_PROP_DONE_OK) {
@ -743,7 +763,7 @@ transmit(unsigned short transmit_len)
* Disable LAST_FG_COMMAND_DONE interrupt. We don't really care about it
* except when we are transmitting
*/
rf_core_cmd_done_dis(false);
rf_core_cmd_done_dis();
/* Workaround. Set status to IDLE */
cmd_tx_adv->status = RF_CORE_RADIO_OP_STATUS_IDLE;
@ -764,47 +784,98 @@ send(const void *payload, unsigned short payload_len)
return transmit(payload_len);
}
/*---------------------------------------------------------------------------*/
static int
read_frame(void *buf, unsigned short buf_len)
static void
release_data_entry(void)
{
int_master_status_t status;
rfc_dataEntryGeneral_t *entry = (rfc_dataEntryGeneral_t *)rx_read_entry;
uint8_t *data_ptr = &entry->data;
int len = 0;
int_master_status_t interrupt_status;
if(entry->status == DATA_ENTRY_STATUS_FINISHED) {
/* Clear the length field (2 bytes) */
data_ptr[0] = 0;
data_ptr[1] = 0;
/*
* First 2 bytes in the data entry are the length.
* Our data entry consists of: Payload + RSSI (1 byte) + Status (1 byte)
* This length includes all of those.
*/
len = (*(uint16_t *)data_ptr);
data_ptr += 2;
len -= 2;
/* Set status to 0 "Pending" in element */
entry->status = DATA_ENTRY_STATUS_PENDING;
rx_read_entry = entry->pNextEntry;
if(len > 0) {
if(len <= buf_len) {
memcpy(buf, data_ptr, len);
}
packetbuf_set_attr(PACKETBUF_ATTR_RSSI, (int8_t)data_ptr[len]);
packetbuf_set_attr(PACKETBUF_ATTR_LINK_QUALITY, 0x7F);
}
/* Move read entry pointer to next entry */
rx_read_entry = entry->pNextEntry;
entry->status = DATA_ENTRY_STATUS_PENDING;
}
status = critical_enter();
if(rx_is_full) {
rx_is_full = false;
interrupt_status = critical_enter();
if(rf_core_rx_is_full) {
rf_core_rx_is_full = false;
PRINTF("RXQ was full, re-enabling radio!\n");
rx_on_prop();
}
critical_exit(status);
critical_exit(interrupt_status);
}
/*---------------------------------------------------------------------------*/
static int
read_frame(void *buf, unsigned short buf_len)
{
rfc_dataEntryGeneral_t *entry = (rfc_dataEntryGeneral_t *)rx_read_entry;
uint8_t *data_ptr = &entry->data;
int len = 0;
uint32_t rat_timestamp;
/* wait for entry to become finished */
rtimer_clock_t t0 = RTIMER_NOW();
while(entry->status == DATA_ENTRY_STATUS_BUSY
&& RTIMER_CLOCK_LT(RTIMER_NOW(), t0 + (RTIMER_SECOND / 50)));
/* Make sure the flag is reset */
is_receiving_packet = 0;
if(entry->status != DATA_ENTRY_STATUS_FINISHED) {
/* No available data */
return 0;
}
/*
* First 2 bytes in the data entry are the length.
* Our data entry consists of:
* Payload + RSSI (1 byte) + Timestamp (4 bytes) + Status (1 byte)
* This length includes all of those.
*/
len = (*(uint16_t *)data_ptr);
if(len <= RX_BUF_METADATA_SIZE) {
PRINTF("RF: too short!");
release_data_entry();
return 0;
}
data_ptr += 2;
len -= RX_BUF_METADATA_SIZE;
if(len > buf_len) {
PRINTF("RF: too long\n");
release_data_entry();
return 0;
}
memcpy(buf, data_ptr, len);
/* get the RSSI and status */
rf_core_last_rssi = (int8_t)data_ptr[len];
rf_core_last_corr_lqi = data_ptr[len + 5];
/* get the timestamp */
memcpy(&rat_timestamp, data_ptr + len + 1, 4);
rf_core_last_packet_timestamp = rf_core_convert_rat_to_rtimer(rat_timestamp);
if(!rf_core_poll_mode) {
/* Not in poll mode: packetbuf should not be accessed in interrupt context.
* In poll mode, the last packet RSSI and link quality can be obtained through
* RADIO_PARAM_LAST_RSSI and RADIO_PARAM_LAST_LINK_QUALITY */
packetbuf_set_attr(PACKETBUF_ATTR_RSSI, rf_core_last_rssi);
packetbuf_set_attr(PACKETBUF_ATTR_LINK_QUALITY, rf_core_last_corr_lqi);
}
release_data_entry();
return len;
}
/*---------------------------------------------------------------------------*/
@ -813,14 +884,14 @@ channel_clear(void)
{
uint8_t was_off = 0;
uint32_t cmd_status;
int8_t rssi = RF_CMD_CCA_REQ_RSSI_UNKNOWN;
int8_t rssi = RF_CORE_CMD_CCA_REQ_RSSI_UNKNOWN;
/*
* If we are in the middle of a BLE operation, we got called by ContikiMAC
* from within an interrupt context. Indicate a clear channel
*/
if(rf_ble_is_active() == RF_BLE_ACTIVE) {
return RF_CCA_CLEAR;
return RF_CORE_CCA_CLEAR;
}
if(!rf_core_is_accessible()) {
@ -830,16 +901,16 @@ channel_clear(void)
if(was_off) {
off();
}
return RF_CCA_CLEAR;
return RF_CORE_CCA_CLEAR;
}
} else {
if(transmitting()) {
PRINTF("channel_clear: called while in TX\n");
return RF_CCA_CLEAR;
return RF_CORE_CCA_CLEAR;
}
}
while(rssi == RF_CMD_CCA_REQ_RSSI_UNKNOWN || rssi == 0) {
while(rssi == RF_CORE_CMD_CCA_REQ_RSSI_UNKNOWN || rssi == 0) {
if(rf_core_send_cmd(CMDR_DIR_CMD(CMD_GET_RSSI), &cmd_status)
!= RF_CORE_CMD_OK) {
break;
@ -853,10 +924,10 @@ channel_clear(void)
}
if(rssi >= rssi_threshold) {
return RF_CCA_BUSY;
return RF_CORE_CCA_BUSY;
}
return RF_CCA_CLEAR;
return RF_CORE_CCA_CLEAR;
}
/*---------------------------------------------------------------------------*/
static int
@ -866,11 +937,23 @@ receiving_packet(void)
return 0;
}
if(channel_clear() == RF_CCA_CLEAR) {
return 0;
if(!is_receiving_packet) {
/* Look for the modem synchronization word detection interrupt flag.
* This flag is raised when the synchronization word is received.
*/
if(HWREG(RFC_DBELL_BASE + RFC_DBELL_O_RFHWIFG) & RFC_DBELL_RFHWIFG_MDMSOFT) {
is_receiving_packet = 1;
}
} else {
/* After the start of the packet: reset the Rx flag once the channel gets clear */
is_receiving_packet = (channel_clear() == RF_CORE_CCA_BUSY);
if(!is_receiving_packet) {
/* Clear the modem sync flag */
ti_lib_rfc_hw_int_clear(RFC_DBELL_RFHWIFG_MDMSOFT);
}
}
return 1;
return is_receiving_packet;
}
/*---------------------------------------------------------------------------*/
static int
@ -881,9 +964,12 @@ pending_packet(void)
/* Go through all RX buffers and check their status */
do {
if(entry->status == DATA_ENTRY_STATUS_FINISHED) {
rv += 1;
process_poll(&rf_core_process);
if(entry->status == DATA_ENTRY_STATUS_FINISHED
|| entry->status == DATA_ENTRY_STATUS_BUSY) {
rv = 1;
if(!rf_core_poll_mode) {
process_poll(&rf_core_process);
}
}
entry = (rfc_dataEntry_t *)entry->pNextEntry;
@ -904,18 +990,18 @@ on(void)
return RF_CORE_CMD_OK;
}
/*
* Request the HF XOSC as the source for the HF clock. Needed before we can
* use the FS. This will only request, it will _not_ perform the switch.
*/
oscillators_request_hf_xosc();
if(rf_is_on()) {
PRINTF("on: We were on. PD=%u, RX=0x%04x \n", rf_core_is_accessible(),
smartrf_settings_cmd_prop_rx_adv.status);
return RF_CORE_CMD_OK;
}
/*
* Request the HF XOSC as the source for the HF clock. Needed before we can
* use the FS. This will only request, it will _not_ perform the switch.
*/
oscillators_request_hf_xosc();
if(!rf_core_is_accessible()) {
if(rf_core_power_up() != RF_CORE_CMD_OK) {
PRINTF("on: rf_core_power_up() failed\n");
@ -958,7 +1044,7 @@ on(void)
}
}
rf_core_setup_interrupts(false);
rf_core_setup_interrupts();
init_rx_buffers();
@ -985,6 +1071,9 @@ on(void)
static int
off(void)
{
int i;
rfc_dataEntry_t *entry;
/*
* If we are in the middle of a BLE operation, we got called by ContikiMAC
* from within an interrupt context. Abort, but pretend everything is OK.
@ -998,15 +1087,39 @@ off(void)
ENERGEST_OFF(ENERGEST_TYPE_LISTEN);
#if !CC2650_FAST_RADIO_STARTUP
/* Switch HF clock source to the RCOSC to preserve power */
oscillators_switch_to_hf_rc();
#endif
/* We pulled the plug, so we need to restore the status manually */
smartrf_settings_cmd_prop_rx_adv.status = RF_CORE_RADIO_OP_STATUS_IDLE;
/*
* Just in case there was an ongoing RX (which started after we begun the
* shutdown sequence), we don't want to leave the buffer in state == ongoing
*/
for(i = 0; i < PROP_MODE_RX_BUF_CNT; i++) {
entry = (rfc_dataEntry_t *)rx_buf[i];
if(entry->status == DATA_ENTRY_STATUS_BUSY) {
entry->status = DATA_ENTRY_STATUS_PENDING;
}
}
return RF_CORE_CMD_OK;
}
/*---------------------------------------------------------------------------*/
/* Enable or disable CCA before sending */
static radio_result_t
set_send_on_cca(uint8_t enable)
{
if(enable) {
/* this driver does not have support for CCA on Tx */
return RADIO_RESULT_NOT_SUPPORTED;
}
return RADIO_RESULT_OK;
}
/*---------------------------------------------------------------------------*/
static radio_result_t
get_value(radio_param_t param, radio_value_t *value)
{
@ -1022,6 +1135,15 @@ get_value(radio_param_t param, radio_value_t *value)
case RADIO_PARAM_CHANNEL:
*value = (radio_value_t)get_channel();
return RADIO_RESULT_OK;
case RADIO_PARAM_RX_MODE:
*value = 0;
if(rf_core_poll_mode) {
*value |= RADIO_RX_MODE_POLL_MODE;
}
return RADIO_RESULT_OK;
case RADIO_PARAM_TX_MODE:
*value = 0;
return RADIO_RESULT_OK;
case RADIO_PARAM_TXPOWER:
*value = get_tx_power();
return RADIO_RESULT_OK;
@ -1031,7 +1153,7 @@ get_value(radio_param_t param, radio_value_t *value)
case RADIO_PARAM_RSSI:
*value = get_rssi();
if(*value == RF_CMD_CCA_REQ_RSSI_UNKNOWN) {
if(*value == RF_CORE_CMD_CCA_REQ_RSSI_UNKNOWN) {
return RADIO_RESULT_ERROR;
} else {
return RADIO_RESULT_OK;
@ -1048,6 +1170,28 @@ get_value(radio_param_t param, radio_value_t *value)
case RADIO_CONST_TXPOWER_MAX:
*value = OUTPUT_POWER_MAX;
return RADIO_RESULT_OK;
case RADIO_PARAM_LAST_RSSI:
*value = rf_core_last_rssi;
return RADIO_RESULT_OK;
case RADIO_PARAM_LAST_LINK_QUALITY:
*value = rf_core_last_corr_lqi;
return RADIO_RESULT_OK;
case RADIO_CONST_PHY_OVERHEAD:
/* 2 header bytes, 2 or 4 bytes CRC */
*value = (radio_value_t)(DOT_4G_PHR_LEN + CRC_LEN);
return RADIO_RESULT_OK;
case RADIO_CONST_BYTE_AIR_TIME:
*value = (radio_value_t)RADIO_BYTE_AIR_TIME;
return RADIO_RESULT_OK;
case RADIO_CONST_DELAY_BEFORE_TX:
*value = (radio_value_t)RADIO_DELAY_BEFORE_TX;
return RADIO_RESULT_OK;
case RADIO_CONST_DELAY_BEFORE_RX:
*value = (radio_value_t)RADIO_DELAY_BEFORE_RX;
return RADIO_RESULT_OK;
case RADIO_CONST_DELAY_BEFORE_DETECT:
*value = (radio_value_t)RADIO_DELAY_BEFORE_DETECT;
return RADIO_RESULT_OK;
default:
return RADIO_RESULT_NOT_SUPPORTED;
}
@ -1056,8 +1200,8 @@ get_value(radio_param_t param, radio_value_t *value)
static radio_result_t
set_value(radio_param_t param, radio_value_t value)
{
uint8_t was_off = 0;
radio_result_t rv = RADIO_RESULT_OK;
uint8_t old_poll_mode;
switch(param) {
case RADIO_PARAM_POWER_MODE:
@ -1087,6 +1231,25 @@ set_value(radio_param_t param, radio_value_t value)
set_channel((uint8_t)value);
break;
case RADIO_PARAM_RX_MODE:
if(value & ~(RADIO_RX_MODE_POLL_MODE)) {
return RADIO_RESULT_INVALID_VALUE;
}
old_poll_mode = rf_core_poll_mode;
rf_core_poll_mode = (value & RADIO_RX_MODE_POLL_MODE) != 0;
if(rf_core_poll_mode == old_poll_mode) {
return RADIO_RESULT_OK;
}
break;
case RADIO_PARAM_TX_MODE:
if(value & ~(RADIO_TX_MODE_SEND_ON_CCA)) {
return RADIO_RESULT_INVALID_VALUE;
}
return set_send_on_cca((value & RADIO_TX_MODE_SEND_ON_CCA) != 0);
case RADIO_PARAM_TXPOWER:
if(value < TX_POWER_DRIVER[get_tx_power_array_last_element()].dbm ||
value > OUTPUT_POWER_MAX) {
@ -1103,8 +1266,7 @@ set_value(radio_param_t param, radio_value_t value)
}
return RADIO_RESULT_OK;
case RADIO_PARAM_RX_MODE:
return RADIO_RESULT_OK;
case RADIO_PARAM_CCA_THRESHOLD:
rssi_threshold = (int8_t)value;
break;
@ -1112,28 +1274,29 @@ set_value(radio_param_t param, radio_value_t value)
return RADIO_RESULT_NOT_SUPPORTED;
}
/* If we reach here we had no errors. Apply new settings */
/* If off, the new configuration will be applied the next time radio is started */
if(!rf_is_on()) {
was_off = 1;
if(on() != RF_CORE_CMD_OK) {
PRINTF("set_value: on() failed (2)\n");
return RADIO_RESULT_ERROR;
}
return RADIO_RESULT_OK;
}
/* If we reach here we had no errors. Apply new settings */
if(rx_off_prop() != RF_CORE_CMD_OK) {
PRINTF("set_value: rx_off_prop() failed\n");
rv = RADIO_RESULT_ERROR;
}
if(soft_on_prop() != RF_CORE_CMD_OK) {
PRINTF("set_value: rx_on_prop() failed\n");
rv = RADIO_RESULT_ERROR;
/* Restart the radio timer (RAT).
This causes resynchronization between RAT and RTC: useful for TSCH. */
if(rf_core_restart_rat() != RF_CORE_CMD_OK) {
PRINTF("set_value: rf_core_restart_rat() failed\n");
/* do not set the error */
} else {
rf_core_check_rat_overflow();
}
/* If we were off, turn back off */
if(was_off) {
off();
if(soft_on_prop() != RF_CORE_CMD_OK) {
PRINTF("set_value: soft_on_prop() failed\n");
rv = RADIO_RESULT_ERROR;
}
return rv;
@ -1142,6 +1305,15 @@ set_value(radio_param_t param, radio_value_t value)
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 = rf_core_last_packet_timestamp;
return RADIO_RESULT_OK;
}
return RADIO_RESULT_NOT_SUPPORTED;
}
/*---------------------------------------------------------------------------*/

View File

@ -99,12 +99,37 @@ static rfc_radioOp_t *last_radio_op = NULL;
/* A struct holding pointers to the primary mode's abort() and restore() */
static const rf_core_primary_mode_t *primary_mode = NULL;
/*---------------------------------------------------------------------------*/
/* RAT has 32-bit register, overflows once 18 minutes */
#define RAT_RANGE 4294967296ull
/* approximate value */
#define RAT_OVERFLOW_PERIOD_SECONDS (60 * 18)
/* how often to check for the overflow, as a minimum */
#define RAT_OVERFLOW_TIMER_INTERVAL (CLOCK_SECOND * RAT_OVERFLOW_PERIOD_SECONDS / 3)
/* Radio timer (RAT) offset as compared to the rtimer counter (RTC) */
int32_t rat_offset = 0;
static bool rat_offset_known = false;
static int32_t rat_offset;
static bool rat_offset_known;
/* Value during the last read of the RAT register */
static uint32_t rat_last_value;
/* For RAT overflow handling */
static struct ctimer rat_overflow_timer;
static volatile uint32_t rat_overflow_counter;
static rtimer_clock_t rat_last_overflow;
static void rat_overflow_check_timer_cb(void *);
/*---------------------------------------------------------------------------*/
volatile int8_t rf_core_last_rssi = RF_CORE_CMD_CCA_REQ_RSSI_UNKNOWN;
volatile uint8_t rf_core_last_corr_lqi = 0;
volatile uint32_t rf_core_last_packet_timestamp = 0;
/*---------------------------------------------------------------------------*/
/* Are we currently in poll mode? */
uint8_t rf_core_poll_mode = 0;
/*---------------------------------------------------------------------------*/
/* Buffer full flag */
volatile bool rx_is_full = false;
volatile bool rf_core_rx_is_full = false;
/*---------------------------------------------------------------------------*/
PROCESS(rf_core_process, "CC13xx / CC26xx RF driver");
/*---------------------------------------------------------------------------*/
@ -399,8 +424,8 @@ rf_core_set_modesel()
} else if(chip_type == CHIP_TYPE_CC1350) {
HWREG(PRCM_BASE + PRCM_O_RFCMODESEL) = PRCM_RFCMODESEL_CURR_MODE5;
rv = RF_CORE_CMD_OK;
#ifdef ThisLibraryIsFor_CC26x0R2_HaltIfViolated
} else if (chip_type == CHIP_TYPE_CC2640R2) {
#if CPU_FAMILY_CC26X0R2
} else if(chip_type == CHIP_TYPE_CC2640R2) {
HWREG(PRCM_BASE + PRCM_O_RFCMODESEL) = PRCM_RFCMODESEL_CURR_MODE1;
rv = RF_CORE_CMD_OK;
#endif
@ -451,10 +476,10 @@ rf_core_restart_rat(void)
}
/*---------------------------------------------------------------------------*/
void
rf_core_setup_interrupts(bool poll_mode)
rf_core_setup_interrupts(void)
{
bool interrupts_disabled;
const uint32_t enabled_irqs = poll_mode ? ENABLED_IRQS_POLL_MODE : ENABLED_IRQS;
const uint32_t enabled_irqs = rf_core_poll_mode ? ENABLED_IRQS_POLL_MODE : ENABLED_IRQS;
/* We are already turned on by the caller, so this should not happen */
if(!rf_core_is_accessible()) {
@ -485,19 +510,23 @@ rf_core_setup_interrupts(bool poll_mode)
}
/*---------------------------------------------------------------------------*/
void
rf_core_cmd_done_en(bool fg, bool poll_mode)
rf_core_cmd_done_en(bool fg)
{
uint32_t irq = fg ? IRQ_LAST_FG_COMMAND_DONE : IRQ_LAST_COMMAND_DONE;
const uint32_t enabled_irqs = poll_mode ? ENABLED_IRQS_POLL_MODE : ENABLED_IRQS;
uint32_t irq = 0;
const uint32_t enabled_irqs = rf_core_poll_mode ? ENABLED_IRQS_POLL_MODE : ENABLED_IRQS;
if(!rf_core_poll_mode) {
irq = fg ? IRQ_LAST_FG_COMMAND_DONE : IRQ_LAST_COMMAND_DONE;
}
HWREG(RFC_DBELL_NONBUF_BASE + RFC_DBELL_O_RFCPEIFG) = enabled_irqs;
HWREG(RFC_DBELL_NONBUF_BASE + RFC_DBELL_O_RFCPEIEN) = enabled_irqs | irq;
}
/*---------------------------------------------------------------------------*/
void
rf_core_cmd_done_dis(bool poll_mode)
rf_core_cmd_done_dis(void)
{
const uint32_t enabled_irqs = poll_mode ? ENABLED_IRQS_POLL_MODE : ENABLED_IRQS;
const uint32_t enabled_irqs = rf_core_poll_mode ? ENABLED_IRQS_POLL_MODE : ENABLED_IRQS;
HWREG(RFC_DBELL_NONBUF_BASE + RFC_DBELL_O_RFCPEIEN) = enabled_irqs;
}
/*---------------------------------------------------------------------------*/
@ -544,6 +573,123 @@ rf_core_primary_mode_restore()
return RF_CORE_CMD_ERROR;
}
/*---------------------------------------------------------------------------*/
uint8_t
rf_core_rat_init(void)
{
rat_last_value = HWREG(RFC_RAT_BASE + RATCNT);
ctimer_set(&rat_overflow_timer, RAT_OVERFLOW_TIMER_INTERVAL,
rat_overflow_check_timer_cb, NULL);
return 1;
}
/*---------------------------------------------------------------------------*/
uint8_t
rf_core_check_rat_overflow(void)
{
uint32_t rat_current_value;
uint8_t interrupts_disabled;
/* Bail out if the RF is not on */
if(primary_mode == NULL || !primary_mode->is_on()) {
return 0;
}
interrupts_disabled = ti_lib_int_master_disable();
rat_current_value = HWREG(RFC_RAT_BASE + RATCNT);
if(rat_current_value + RAT_RANGE / 4 < rat_last_value) {
/* Overflow detected */
rat_last_overflow = RTIMER_NOW();
rat_overflow_counter++;
}
rat_last_value = rat_current_value;
if(!interrupts_disabled) {
ti_lib_int_master_enable();
}
return 1;
}
/*---------------------------------------------------------------------------*/
static void
rat_overflow_check_timer_cb(void *unused)
{
uint8_t success = 0;
uint8_t was_off = 0;
if(primary_mode != NULL) {
if(!primary_mode->is_on()) {
was_off = 1;
if(NETSTACK_RADIO.on() != RF_CORE_CMD_OK) {
PRINTF("overflow: on() failed\n");
ctimer_set(&rat_overflow_timer, CLOCK_SECOND,
rat_overflow_check_timer_cb, NULL);
return;
}
}
success = rf_core_check_rat_overflow();
if(was_off) {
NETSTACK_RADIO.off();
}
}
if(success) {
/* Retry after half of the interval */
ctimer_set(&rat_overflow_timer, RAT_OVERFLOW_TIMER_INTERVAL,
rat_overflow_check_timer_cb, NULL);
} else {
/* Retry sooner */
ctimer_set(&rat_overflow_timer, CLOCK_SECOND,
rat_overflow_check_timer_cb, NULL);
}
}
/*---------------------------------------------------------------------------*/
uint32_t
rf_core_convert_rat_to_rtimer(uint32_t rat_timestamp)
{
uint64_t rat_timestamp64;
uint32_t adjusted_overflow_counter;
uint8_t was_off = 0;
if(primary_mode == NULL) {
PRINTF("rf_core_convert_rat_to_rtimer: not initialized\n");
return 0;
}
if(!primary_mode->is_on()) {
was_off = 1;
NETSTACK_RADIO.on();
}
rf_core_check_rat_overflow();
if(was_off) {
NETSTACK_RADIO.off();
}
adjusted_overflow_counter = rat_overflow_counter;
/* if the timestamp is large and the last oveflow was recently,
assume that the timestamp refers to the time before the overflow */
if(rat_timestamp > (uint32_t)(RAT_RANGE * 3 / 4)) {
if(RTIMER_CLOCK_LT(RTIMER_NOW(),
rat_last_overflow + RAT_OVERFLOW_PERIOD_SECONDS * RTIMER_SECOND / 4)) {
adjusted_overflow_counter--;
}
}
/* add the overflowed time to the timestamp */
rat_timestamp64 = rat_timestamp + RAT_RANGE * adjusted_overflow_counter;
/* correct timestamp so that it refers to the end of the SFD */
rat_timestamp64 += primary_mode->sfd_timestamp_offset;
return RADIO_TO_RTIMER(rat_timestamp64 - rat_offset);
}
/*---------------------------------------------------------------------------*/
PROCESS_THREAD(rf_core_process, ev, data)
{
int len;
@ -582,11 +728,11 @@ cc26xx_rf_cpe1_isr(void)
return;
}
}
if(HWREG(RFC_DBELL_NONBUF_BASE + RFC_DBELL_O_RFCPEIFG) & IRQ_RX_BUF_FULL) {
PRINTF("\nRF: BUF_FULL\n\n");
/* set a flag that the buffer is full*/
rx_is_full = true;
rf_core_rx_is_full = true;
/* make sure read_frame() will be called to make space in RX buffer */
process_poll(&rf_core_process);
/* Clear the IRQ_RX_BUF_FULL interrupt flag by writing zero to bit */

View File

@ -133,6 +133,17 @@ typedef struct rf_core_primary_mode_s {
* \return RF_CORE_CMD_OK or RF_CORE_CMD_ERROR
*/
uint8_t (*restore)(void);
/**
* \brief A pointer to a function that checks if the radio is on
* \return 1 or 0
*/
uint8_t (*is_on)(void);
/**
* \brief Offset of the end of SFD when compared to the radio HW-generated timestamp
*/
int16_t sfd_timestamp_offset;
} rf_core_primary_mode_t;
/*---------------------------------------------------------------------------*/
/* RF Command status constants - Correspond to values in the CMDSTA register */
@ -263,12 +274,65 @@ typedef struct rf_core_primary_mode_s {
/* Radio timer register */
#define RATCNT 0x00000004
/*---------------------------------------------------------------------------*/
/* Buffer full flag */
extern volatile bool rx_is_full;
/* Special value returned by CMD_IEEE_CCA_REQ when an RSSI is not available */
#define RF_CORE_CMD_CCA_REQ_RSSI_UNKNOWN -128
/* Used for the return value of channel_clear */
#define RF_CORE_CCA_CLEAR 1
#define RF_CORE_CCA_BUSY 0
/* Used as an error return value for get_cca_info */
#define RF_CORE_GET_CCA_INFO_ERROR 0xFF
/*
* Values of the individual bits of the ccaInfo field in CMD_IEEE_CCA_REQ's
* status struct
*/
#define RF_CORE_CMD_CCA_REQ_CCA_STATE_IDLE 0 /* 00 */
#define RF_CORE_CMD_CCA_REQ_CCA_STATE_BUSY 1 /* 01 */
#define RF_CORE_CMD_CCA_REQ_CCA_STATE_INVALID 2 /* 10 */
#define RF_CORE_CMD_CCA_REQ_CCA_CORR_IDLE (0 << 4)
#define RF_CORE_CMD_CCA_REQ_CCA_CORR_BUSY (1 << 4)
#define RF_CORE_CMD_CCA_REQ_CCA_CORR_INVALID (3 << 4)
#define RF_CORE_CMD_CCA_REQ_CCA_CORR_MASK (3 << 4)
#define RF_CORE_CMD_CCA_REQ_CCA_SYNC_BUSY (1 << 6)
/*---------------------------------------------------------------------------*/
#define RF_CORE_RX_BUF_INCLUDE_CRC 0
#define RF_CORE_RX_BUF_INCLUDE_RSSI 1
#define RF_CORE_RX_BUF_INCLUDE_CORR 1
#define RF_CORE_RX_BUF_INCLUDE_TIMESTAMP 1
/*---------------------------------------------------------------------------*/
/* How long to wait for an ongoing ACK TX to finish before starting frame TX */
#define RF_CORE_TX_TIMEOUT (RTIMER_SECOND >> 11)
/* How long to wait for the RF to enter RX in rf_cmd_ieee_rx */
#define RF_CORE_ENTER_RX_TIMEOUT (RTIMER_SECOND >> 10)
/* How long to wait for the RF to react on CMD_ABORT: around 1 msec */
#define RF_CORE_TURN_OFF_TIMEOUT (RTIMER_SECOND >> 10)
/* How long to wait for the RF to finish TX of a packet or an ACK */
#define RF_CORE_TX_FINISH_TIMEOUT (RTIMER_SECOND >> 7)
/*---------------------------------------------------------------------------*/
/* Make the main driver process visible to mode drivers */
PROCESS_NAME(rf_core_process);
/*---------------------------------------------------------------------------*/
/* Buffer full flag */
extern volatile bool rf_core_rx_is_full;
/*---------------------------------------------------------------------------*/
/* RSSI of the last read frame */
extern volatile int8_t rf_core_last_rssi;
/* Correlation/LQI of the last read frame */
extern volatile uint8_t rf_core_last_corr_lqi;
/* SFD timestamp of the last read frame, in rtimer ticks */
extern volatile uint32_t rf_core_last_packet_timestamp;
/*---------------------------------------------------------------------------*/
/* Are we currently in poll mode? */
extern uint8_t rf_core_poll_mode;
/*---------------------------------------------------------------------------*/
/**
* \brief Check whether the RF core is accessible
* \retval RF_CORE_ACCESSIBLE The core is powered and ready for access
@ -383,20 +447,19 @@ uint8_t rf_core_boot(void);
/**
* \brief Setup RF core interrupts
*/
void rf_core_setup_interrupts(bool poll_mode);
void rf_core_setup_interrupts(void);
/**
* \brief Enable interrupt on command done.
* \param fg set true to enable irq on foreground command done and false for
* background commands or if not in ieee mode.
* \param poll_mode true if the driver is in poll mode
*
* This is used within TX routines in order to be able to sleep the CM3 and
* wake up after TX has finished
*
* \sa rf_core_cmd_done_dis()
*/
void rf_core_cmd_done_en(bool fg, bool poll_mode);
void rf_core_cmd_done_en(bool fg);
/**
* \brief Disable the LAST_CMD_DONE and LAST_FG_CMD_DONE interrupts.
@ -405,7 +468,7 @@ void rf_core_cmd_done_en(bool fg, bool poll_mode);
*
* \sa rf_core_cmd_done_en()
*/
void rf_core_cmd_done_dis(bool poll_mode);
void rf_core_cmd_done_dis(void);
/**
* \brief Returns a pointer to the most recent proto-dependent Radio Op
@ -467,6 +530,22 @@ void rf_core_primary_mode_abort(void);
* \brief Abort the currently running primary radio op
*/
uint8_t rf_core_primary_mode_restore(void);
/**
* \brief Initialize the RAT to RTC conversion machinery
*/
uint8_t rf_core_rat_init(void);
/**
* \brief Check if RAT overflow has occured and increment the overflow counter if so
*/
uint8_t rf_core_check_rat_overflow(void);
/**
* \brief Convert from RAT timestamp to rtimer ticks
*/
uint32_t rf_core_convert_rat_to_rtimer(uint32_t rat_timestamp);
/*---------------------------------------------------------------------------*/
#endif /* RF_CORE_H_ */
/*---------------------------------------------------------------------------*/

View File

@ -1,195 +0,0 @@
/*
* Copyright (c) 2016, 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-ti-lib
* @{
*
* \file
* Header file with CC13xxware/CC26xxware ROM API.
*/
/*---------------------------------------------------------------------------*/
#ifndef TI_LIB_ROM_H_
#define TI_LIB_ROM_H_
/*---------------------------------------------------------------------------*/
/* rom.h */
#include "driverlib/rom.h"
/* AON API */
#define ti_lib_rom_aon_event_mcu_wake_up_set ROM_AONEventMcuWakeUpSet
#define ti_lib_rom_aon_event_mcu_wake_up_get ROM_AONEventMcuWakeUpGet
#define ti_lib_rom_aon_event_aux_wake_up_set ROM_AONEventAuxWakeUpSet
#define ti_lib_rom_aon_event_aux_wake_up_get ROM_AONEventAuxWakeUpGet
#define ti_lib_rom_aon_event_mcu_set ROM_AONEventMcuSet
#define ti_lib_rom_aon_event_mcu_get ROM_AONEventMcuGet
/* AON_WUC API */
#define ti_lib_rom_aon_wuc_aux_reset ROM_AONWUCAuxReset
#define ti_lib_rom_aon_wuc_recharge_ctrl_config_set ROM_AONWUCRechargeCtrlConfigSet
#define ti_lib_rom_aon_wuc_osc_config ROM_AONWUCOscConfig
/* AUX_TDC API */
#define ti_lib_rom_aux_tdc_config_set ROM_AUXTDCConfigSet
#define ti_lib_rom_aux_tdc_measurement_done ROM_AUXTDCMeasurementDone
/* AUX_WUC API */
#define ti_lib_rom_aux_wuc_clock_enable ROM_AUXWUCClockEnable
#define ti_lib_rom_aux_wuc_clock_disable ROM_AUXWUCClockDisable
#define ti_lib_rom_aux_wuc_clock_status ROM_AUXWUCClockStatus
#define ti_lib_rom_aux_wuc_power_ctrl ROM_AUXWUCPowerCtrl
/* FLASH API */
#define ti_lib_rom_flash_power_mode_get ROM_FlashPowerModeGet
#define ti_lib_rom_flash_protection_set ROM_FlashProtectionSet
#define ti_lib_rom_flash_protection_get ROM_FlashProtectionGet
#define ti_lib_rom_flash_protection_save ROM_FlashProtectionSave
#define ti_lib_rom_flash_efuse_read_row ROM_FlashEfuseReadRow
#define ti_lib_rom_flash_disable_sectors_for_write ROM_FlashDisableSectorsForWrite
/* I2C API */
#define ti_lib_rom_i2c_master_init_exp_clk ROM_I2CMasterInitExpClk
#define ti_lib_rom_i2c_master_err ROM_I2CMasterErr
/* INTERRUPT API */
#define ti_lib_rom_int_priority_grouping_set ROM_IntPriorityGroupingSet
#define ti_lib_rom_int_priority_grouping_get ROM_IntPriorityGroupingGet
#define ti_lib_rom_int_priority_set ROM_IntPrioritySet
#define ti_lib_rom_int_priority_get ROM_IntPriorityGet
#define ti_lib_rom_int_enable ROM_IntEnable
#define ti_lib_rom_int_disable ROM_IntDisable
#define ti_lib_rom_int_pend_set ROM_IntPendSet
#define ti_lib_rom_int_pend_get ROM_IntPendGet
#define ti_lib_rom_int_pend_clear ROM_IntPendClear
/* IOC API */
#define ti_lib_rom_ioc_port_configure_set ROM_IOCPortConfigureSet
#if !defined(ThisLibraryIsFor_CC26x0R2_HaltIfViolated)
#define ti_lib_rom_ioc_port_configure_get ROM_IOCPortConfigureGet
#define ti_lib_rom_ioc_io_shutdown_set ROM_IOCIOShutdownSet
#define ti_lib_rom_ioc_io_mode_set ROM_IOCIOModeSet
#define ti_lib_rom_ioc_io_int_set ROM_IOCIOIntSet
#define ti_lib_rom_ioc_io_port_pull_set ROM_IOCIOPortPullSet
#define ti_lib_rom_ioc_io_hyst_set ROM_IOCIOHystSet
#define ti_lib_rom_ioc_io_input_set ROM_IOCIOInputSet
#define ti_lib_rom_ioc_io_slew_ctrl_set ROM_IOCIOSlewCtrlSet
#define ti_lib_rom_ioc_io_drv_strength_set ROM_IOCIODrvStrengthSet
#define ti_lib_rom_ioc_io_port_id_set ROM_IOCIOPortIdSet
#define ti_lib_rom_ioc_int_enable ROM_IOCIntEnable
#define ti_lib_rom_ioc_int_disable ROM_IOCIntDisable
#define ti_lib_rom_ioc_pin_type_gpio_input ROM_IOCPinTypeGpioInput
#define ti_lib_rom_ioc_pin_type_gpio_output ROM_IOCPinTypeGpioOutput
#define ti_lib_rom_ioc_pin_type_uart ROM_IOCPinTypeUart
#define ti_lib_rom_ioc_pin_type_ssi_master ROM_IOCPinTypeSsiMaster
#define ti_lib_rom_ioc_pin_type_ssi_slave ROM_IOCPinTypeSsiSlave
#define ti_lib_rom_ioc_pin_type_i2c ROM_IOCPinTypeI2c
#define ti_lib_rom_ioc_pin_type_aux ROM_IOCPinTypeAux
#endif
/* PRCM API */
#define ti_lib_rom_prcm_inf_clock_configure_set ROM_PRCMInfClockConfigureSet
#define ti_lib_rom_prcm_inf_clock_configure_get ROM_PRCMInfClockConfigureGet
#define ti_lib_rom_prcm_audio_clock_config_set ROM_PRCMAudioClockConfigSet
#define ti_lib_rom_prcm_power_domain_on ROM_PRCMPowerDomainOn
#define ti_lib_rom_prcm_power_domain_off ROM_PRCMPowerDomainOff
#define ti_lib_rom_prcm_peripheral_run_enable ROM_PRCMPeripheralRunEnable
#define ti_lib_rom_prcm_peripheral_run_disable ROM_PRCMPeripheralRunDisable
#define ti_lib_rom_prcm_peripheral_sleep_enable ROM_PRCMPeripheralSleepEnable
#define ti_lib_rom_prcm_peripheral_sleep_disable ROM_PRCMPeripheralSleepDisable
#define ti_lib_rom_prcm_peripheral_deep_sleep_enable ROM_PRCMPeripheralDeepSleepEnable
#define ti_lib_rom_prcm_peripheral_deep_sleep_disable ROM_PRCMPeripheralDeepSleepDisable
#define ti_lib_rom_prcm_power_domain_status ROM_PRCMPowerDomainStatus
#define ti_lib_rom_prcm_deep_sleep ROM_PRCMDeepSleep
/* SMPH API */
#define ti_lib_rom_smph_acquire ROM_SMPHAcquire
/* SSI API */
#define ti_lib_rom_ssi_config_set_exp_clk ROM_SSIConfigSetExpClk
#define ti_lib_rom_ssi_data_put ROM_SSIDataPut
#define ti_lib_rom_ssi_data_put_non_blocking ROM_SSIDataPutNonBlocking
#define ti_lib_rom_ssi_data_get ROM_SSIDataGet
#define ti_lib_rom_ssi_data_get_non_blocking ROM_SSIDataGetNonBlocking
/* TIMER API */
#define ti_lib_rom_timer_configure ROM_TimerConfigure
#define ti_lib_rom_timer_level_control ROM_TimerLevelControl
#define ti_lib_rom_timer_stall_control ROM_TimerStallControl
#define ti_lib_rom_timer_wait_on_trigger_control ROM_TimerWaitOnTriggerControl
/* TRNG API */
#define ti_lib_rom_trng_number_get ROM_TRNGNumberGet
/* UART API */
#define ti_lib_rom_uart_fifo_level_get ROM_UARTFIFOLevelGet
#define ti_lib_rom_uart_config_set_exp_clk ROM_UARTConfigSetExpClk
#define ti_lib_rom_uart_config_get_exp_clk ROM_UARTConfigGetExpClk
#define ti_lib_rom_uart_disable ROM_UARTDisable
#define ti_lib_rom_uart_char_get_non_blocking ROM_UARTCharGetNonBlocking
#define ti_lib_rom_uart_char_get ROM_UARTCharGet
#define ti_lib_rom_uart_char_put_non_blocking ROM_UARTCharPutNonBlocking
#define ti_lib_rom_uart_char_put ROM_UARTCharPut
/* UDMA API */
#define ti_lib_rom_udma_channel_attribute_enable ROM_uDMAChannelAttributeEnable
#define ti_lib_rom_udma_channel_attribute_disable ROM_uDMAChannelAttributeDisable
#define ti_lib_rom_udma_channel_attribute_get ROM_uDMAChannelAttributeGet
#define ti_lib_rom_udma_channel_control_set ROM_uDMAChannelControlSet
#define ti_lib_rom_udma_channel_transfer_set ROM_uDMAChannelTransferSet
#define ti_lib_rom_udma_channel_scatter_gather_set ROM_uDMAChannelScatterGatherSet
#define ti_lib_rom_udma_channel_size_get ROM_uDMAChannelSizeGet
#define ti_lib_rom_udma_channel_mode_get ROM_uDMAChannelModeGet
/* VIMS API */
#define ti_lib_rom_vims_configure ROM_VIMSConfigure
#define ti_lib_rom_vims_mode_set ROM_VIMSModeSet
/* HAPI */
#define ti_lib_hapi_crc32(a, b, c) HapiCrc32(a, b, c)
#define ti_lib_hapi_get_flash_size() HapiGetFlashSize()
#define ti_lib_hapi_get_chip_id() HapiGetChipId()
#define ti_lib_hapi_sector_erase(a) HapiSectorErase(a)
#define ti_lib_hapi_program_flash(a, b, c) HapiProgramFlash(a, b, c)
#define ti_lib_hapi_reset_device() HapiResetDevice()
#define ti_lib_hapi_fletcher32(a, b, c) HapiFletcher32(a, b, c)
#define ti_lib_hapi_min_value(a, b) HapiMinValue(a,b)
#define ti_lib_hapi_max_value(a, b) HapiMaxValue(a,b)
#define ti_lib_hapi_mean_value(a, b) HapiMeanValue(a,b)
#define ti_lib_hapi_stand_deviation_value(a, b) HapiStandDeviationValue(a,b)
#define ti_lib_hapi_hf_source_safe_switch() HapiHFSourceSafeSwitch()
#define ti_lib_hapi_select_comp_a_input(a) HapiSelectCompAInput(a)
#define ti_lib_hapi_select_comp_a_ref(a) HapiSelectCompARef(a)
#define ti_lib_hapi_select_adc_comp_b_input(a) HapiSelectADCCompBInput(a)
#define ti_lib_hapi_select_comp_b_ref(a) HapiSelectCompBRef(a)
/*---------------------------------------------------------------------------*/
#endif /* TI_LIB_ROM_H_ */
/*---------------------------------------------------------------------------*/
/**
* @}
*/

View File

@ -52,9 +52,6 @@
#ifndef TI_LIB_H_
#define TI_LIB_H_
/*---------------------------------------------------------------------------*/
/* Include ROM API */
#include "ti-lib-rom.h"
/*---------------------------------------------------------------------------*/
/* aon_batmon.h */
#include "driverlib/aon_batmon.h"
@ -200,14 +197,16 @@
#define ti_lib_chipinfo_get_device_id_hw_rev_code(...) ChipInfo_GetDeviceIdHwRevCode(__VA_ARGS__)
#define ti_lib_chipinfo_get_chip_type(...) ChipInfo_GetChipType(__VA_ARGS__)
#define ti_lib_chipinfo_get_chip_family(...) ChipInfo_GetChipFamily(__VA_ARGS__)
#ifdef ThisLibraryIsFor_CC26x0R2_HaltIfViolated
#if CPU_FAMILY_CC26X0R2
#define ti_lib_chipinfo_chip_family_is_cc26xx(...) ChipInfo_ChipFamilyIs_CC26x0(__VA_ARGS__)
#define ti_lib_chipinfo_chip_family_is_cc13xx(...) ChipInfo_ChipFamilyIs_CC13x0(__VA_ARGS__)
#define ti_lib_chipinfo_chip_family_is_cc26x0r2(...) ChipInfo_ChipFamilyIs_CC26x0R2(__VA_ARGS__)
#define ti_lib_chipinfo_chip_family_is_cc26x0r2(...) ChipInfo_ChipFamilyIs_CC26x0R2(__VA_ARGS__)
#else
#define ti_lib_chipinfo_chip_family_is_cc26xx(...) ChipInfo_ChipFamilyIsCC26xx(__VA_ARGS__)
#define ti_lib_chipinfo_chip_family_is_cc13xx(...) ChipInfo_ChipFamilyIsCC13xx(__VA_ARGS__)
#endif
#endif /* CPU_FAMILY_CC26X0R2 */
#define ti_lib_chipinfo_get_hw_revision(...) ChipInfo_GetHwRevision(__VA_ARGS__)
#define ti_lib_chipinfo_hw_revision_is_1_0(...) ChipInfo_HwRevisionIs_1_0(__VA_ARGS__)
#define ti_lib_chipinfo_hw_revision_is_gteq_2_0(...) ChipInfo_HwRevisionIs_GTEQ_2_0(__VA_ARGS__)
@ -394,16 +393,15 @@
#define ti_lib_pwr_ctrl_source_get(...) PowerCtrlSourceGet(__VA_ARGS__)
#define ti_lib_pwr_ctrl_reset_source_get(...) PowerCtrlResetSourceGet(__VA_ARGS__)
#define ti_lib_pwr_ctrl_reset_source_clear(...) PowerCtrlResetSourceClear(__VA_ARGS__)
#if !defined(ThisLibraryIsFor_CC26x0R2_HaltIfViolated)
#define ti_lib_pwr_ctrl_io_freeze_enable(...) PowerCtrlIOFreezeEnable(__VA_ARGS__)
#define ti_lib_pwr_ctrl_io_freeze_disable(...) PowerCtrlIOFreezeDisable(__VA_ARGS__)
#endif
/*---------------------------------------------------------------------------*/
/* rfc.h */
#include "driverlib/rfc.h"
#define ti_lib_rfc_rtrim(...) RFCRTrim(__VA_ARGS__)
#define ti_lib_rfc_adi3vco_ldo_voltage_mode(...) RFCAdi3VcoLdoVoltageMode(__VA_ARGS__)
#define ti_lib_rfc_hw_int_enable(...) RFCHwIntEnable(__VA_ARGS__)
#define ti_lib_rfc_hw_int_disable(...) RFCHwIntDisable(__VA_ARGS__)
#define ti_lib_rfc_hw_int_clear(...) RFCHwIntClear(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* sys_ctrl.h */
#include "driverlib/sys_ctrl.h"
@ -416,7 +414,14 @@
#define ti_lib_sys_ctrl_aon_sync(...) SysCtrlAonSync(__VA_ARGS__)
#define ti_lib_sys_ctrl_aon_update(...) SysCtrlAonUpdate(__VA_ARGS__)
#define ti_lib_sys_ctrl_set_recharge_before_power_down(...) SysCtrlSetRechargeBeforePowerDown(__VA_ARGS__)
#define ti_lib_sys_ctrl_adjust_recharge_after_power_down(...) SysCtrlAdjustRechargeAfterPowerDown(__VA_ARGS__)
#if CPU_FAMILY_CC26X0R2
/* May need to change to XOSC_IN_LOW_POWER_MODE */
#define ti_lib_sys_ctrl_adjust_recharge_after_power_down() SysCtrlAdjustRechargeAfterPowerDown(XOSC_IN_HIGH_POWER_MODE)
#else
#define ti_lib_sys_ctrl_adjust_recharge_after_power_down() SysCtrlAdjustRechargeAfterPowerDown()
#endif /* CPU_FAMILY_CC26X0R2 */
#define ti_lib_sys_ctrl_dcdc_voltage_conditional_control(...) SysCtrl_DCDC_VoltageConditionalControl(__VA_ARGS__)
#define ti_lib_sys_ctrl_reset_source_get(...) SysCtrlResetSourceGet(__VA_ARGS__)
#define ti_lib_sys_ctrl_system_reset(...) SysCtrlSystemReset(__VA_ARGS__)

View File

@ -20,6 +20,30 @@ endif
CFLAGSNO = -Wall -g -I/usr/local/include $(CFLAGSWERROR)
CFLAGS += $(CFLAGSNO)
### Are we building with code size optimisations?
SMALL ?= 0
# The optimizations on native platform cannot be enabled in GCC (not Clang) versions less than 7.2
GCC_IS_CLANG := $(shell gcc --version 2> /dev/null | grep clang)
ifneq ($(GCC_IS_CLANG),)
NATIVE_CAN_OPTIIMIZE = 1
else
GCC_VERSION := $(shell gcc -dumpfullversion -dumpversion | cut -b1-3)
ifeq ($(shell expr $(GCC_VERSION) \>= 7.2), 1)
NATIVE_CAN_OPTIIMIZE = 1
else
NATIVE_CAN_OPTIIMIZE = 0
endif
endif
ifeq ($(NATIVE_CAN_OPTIIMIZE),1)
ifeq ($(SMALL),1)
CFLAGS += -Os
else
CFLAGS += -O2
endif
endif
ifeq ($(HOST_OS),Darwin)
AROPTS = -rc
LDFLAGS_WERROR := -Wl,-fatal_warnings

View File

@ -14,3 +14,5 @@ INCLUDE "nrf5x_common.ld"
/* These symbols are used by the stack check library. */
_stack = end;
_stack_origin = ORIGIN(RAM) + LENGTH(RAM);
_heap = _stack;
_eheap = _stack_origin;

View File

@ -14,3 +14,5 @@ INCLUDE "nrf5x_common.ld"
/* These symbols are used by the stack check library. */
_stack = end;
_stack_origin = ORIGIN(RAM) + LENGTH(RAM);
_heap = _stack;
_eheap = _stack_origin;

View File

@ -14,3 +14,5 @@ INCLUDE "nrf5x_common.ld"
/* These symbols are used by the stack check library. */
_stack = end;
_stack_origin = ORIGIN(RAM) + LENGTH(RAM);
_heap = _stack;
_eheap = _stack_origin;

View File

@ -235,30 +235,6 @@ spi_arch_transfer(const spi_device_t *dev,
return SPI_DEV_STATUS_OK;
}
/*---------------------------------------------------------------------------*/
spi_status_t
spi_arch_select(const spi_device_t *dev)
{
if(!spi_arch_has_lock(dev)) {
return SPI_DEV_STATUS_BUS_NOT_OWNED;
}
PINCC26XX_setOutputValue(dev->pin_spi_cs, 0);
return SPI_DEV_STATUS_OK;
}
/*---------------------------------------------------------------------------*/
spi_status_t
spi_arch_deselect(const spi_device_t *dev)
{
if(!spi_arch_has_lock(dev)) {
return SPI_DEV_STATUS_BUS_NOT_OWNED;
}
PINCC26XX_setOutputValue(dev->pin_spi_cs, 1);
return SPI_DEV_STATUS_OK;
}
/*---------------------------------------------------------------------------*/
/**
* @}
* @}

View File

@ -310,15 +310,7 @@ extern const cc1200_rf_cfg_t CC1200_RF_CFG;
#define LOCK_SPI() do { spi_locked++; } while(0)
#define SPI_IS_LOCKED() (spi_locked != 0)
#define RELEASE_SPI() do { spi_locked--; } while(0)
/*---------------------------------------------------------------------------*/
#define BUSYWAIT_UNTIL(cond, max_time) \
do { \
rtimer_clock_t t0; \
t0 = RTIMER_NOW(); \
while(!(cond) && RTIMER_CLOCK_LT(RTIMER_NOW(), t0 + (max_time))) { \
watchdog_periodic(); \
} \
} while(0)
/*---------------------------------------------------------------------------*/
#if CC1200_USE_GPIO2
/* Configure GPIO interrupts. GPIO0: falling, GPIO2: rising edge */
@ -378,29 +370,9 @@ extern const cc1200_rf_cfg_t CC1200_RF_CFG;
#define INFO(...)
#endif
#if DEBUG_LEVEL > 0
/*
* As BUSYWAIT_UNTIL was mainly used to test for a state transition,
* we define a separate macro for this adding the possibility to
* throw an error message when the timeout exceeds
*/
#define BUSYWAIT_UNTIL_STATE(s, t) \
do { \
rtimer_clock_t t0; \
t0 = RTIMER_NOW(); \
while((state() != s) && RTIMER_CLOCK_LT(RTIMER_NOW(), t0 + (t))) {} \
if(!(RTIMER_CLOCK_LT(RTIMER_NOW(), t0 + (t)))) { \
printf("RF: Timeout exceeded in line %d!\n", __LINE__); \
} \
} while(0)
#else
#define BUSYWAIT_UNTIL_STATE(s, t) \
do { \
rtimer_clock_t t0; \
t0 = RTIMER_NOW(); \
while((state() != s) && RTIMER_CLOCK_LT(RTIMER_NOW(), t0 + (t))) {} \
} while(0)
#endif
/* Busy-wait (time-bounded) until the radio reaches a given state */
#define RTIMER_BUSYWAIT_UNTIL_STATE(s, t) RTIMER_BUSYWAIT_UNTIL(state() == (s), t)
/*---------------------------------------------------------------------------*/
/* Variables */
/*---------------------------------------------------------------------------*/
@ -604,7 +576,7 @@ PROCESS_THREAD(cc1200_process, ev, data)
/*
* We are on and not in TX. As every function of this driver
* assures that we are in RX mode
* (using BUSYWAIT_UNTIL_STATE(STATE_RX, ...) construct) in
* (using RTIMER_BUSYWAIT_UNTIL_STATE(STATE_RX, ...) construct) in
* either rx_rx(), idle_calibrate_rx() or transmit(),
* something probably went wrong in the rx interrupt handler
* if we are not in RX at this point.
@ -893,7 +865,7 @@ transmit(unsigned short transmit_len)
* again as they were turned off in idle()
*/
BUSYWAIT_UNTIL_STATE(STATE_RX,
RTIMER_BUSYWAIT_UNTIL_STATE(STATE_RX,
CC1200_RF_CFG.tx_rx_turnaround);
ENABLE_GPIO_INTERRUPTS();
@ -1033,7 +1005,7 @@ channel_clear(void)
}
/* Wait for CARRIER_SENSE_VALID signal */
BUSYWAIT_UNTIL(((rssi0 = single_read(CC1200_RSSI0))
RTIMER_BUSYWAIT_UNTIL(((rssi0 = single_read(CC1200_RSSI0))
& CC1200_CARRIER_SENSE_VALID),
RTIMER_SECOND / 100);
RF_ASSERT(rssi0 & CC1200_CARRIER_SENSE_VALID);
@ -1135,7 +1107,7 @@ on(void)
/* Wake-up procedure. Wait for GPIO0 to de-assert (CHIP_RDYn) */
cc1200_arch_spi_select();
BUSYWAIT_UNTIL((cc1200_arch_gpio0_read_pin() == 0),
RTIMER_BUSYWAIT_UNTIL((cc1200_arch_gpio0_read_pin() == 0),
RTIMER_SECOND / 100);
RF_ASSERT((cc1200_arch_gpio0_read_pin() == 0));
cc1200_arch_spi_deselect();
@ -1239,7 +1211,7 @@ get_rssi(void)
}
/* Wait for CARRIER_SENSE_VALID signal */
BUSYWAIT_UNTIL(((rssi0 = single_read(CC1200_RSSI0))
RTIMER_BUSYWAIT_UNTIL(((rssi0 = single_read(CC1200_RSSI0))
& CC1200_CARRIER_SENSE_VALID),
RTIMER_SECOND / 100);
RF_ASSERT(rssi0 & CC1200_CARRIER_SENSE_VALID);
@ -1706,20 +1678,20 @@ configure(void)
while(1) {
#if (CC1200_RF_TESTMODE == 1)
watchdog_periodic();
BUSYWAIT_UNTIL(0, RTIMER_SECOND / 10);
RTIMER_BUSYWAIT(RTIMER_SECOND / 10);
leds_off(LEDS_YELLOW);
leds_on(LEDS_RED);
watchdog_periodic();
BUSYWAIT_UNTIL(0, RTIMER_SECOND / 10);
RTIMER_BUSYWAIT(RTIMER_SECOND / 10);
leds_off(LEDS_RED);
leds_on(LEDS_YELLOW);
#else
watchdog_periodic();
BUSYWAIT_UNTIL(0, RTIMER_SECOND / 10);
RTIMER_BUSYWAIT(RTIMER_SECOND / 10);
leds_off(LEDS_GREEN);
leds_on(LEDS_RED);
watchdog_periodic();
BUSYWAIT_UNTIL(0, RTIMER_SECOND / 10);
RTIMER_BUSYWAIT(RTIMER_SECOND / 10);
leds_off(LEDS_RED);
leds_on(LEDS_GREEN);
#endif
@ -1741,11 +1713,11 @@ configure(void)
while(1) {
watchdog_periodic();
BUSYWAIT_UNTIL(0, RTIMER_SECOND / 10);
RTIMER_BUSYWAIT(RTIMER_SECOND / 10);
leds_off(LEDS_GREEN);
leds_on(LEDS_YELLOW);
watchdog_periodic();
BUSYWAIT_UNTIL(0, RTIMER_SECOND / 10);
RTIMER_BUSYWAIT(RTIMER_SECOND / 10);
leds_off(LEDS_YELLOW);
leds_on(LEDS_GREEN);
clock_delay_usec(1000);
@ -1866,8 +1838,8 @@ calibrate(void)
INFO("RF: Calibrate\n");
strobe(CC1200_SCAL);
BUSYWAIT_UNTIL_STATE(STATE_CALIBRATE, RTIMER_SECOND / 100);
BUSYWAIT_UNTIL_STATE(STATE_IDLE, RTIMER_SECOND / 100);
RTIMER_BUSYWAIT_UNTIL_STATE(STATE_CALIBRATE, RTIMER_SECOND / 100);
RTIMER_BUSYWAIT_UNTIL_STATE(STATE_IDLE, RTIMER_SECOND / 100);
#if CC1200_CAL_TIMEOUT_SECONDS
cal_timer = clock_seconds();
@ -1904,7 +1876,7 @@ idle(void)
}
strobe(CC1200_SIDLE);
BUSYWAIT_UNTIL_STATE(STATE_IDLE, RTIMER_SECOND / 100);
RTIMER_BUSYWAIT_UNTIL_STATE(STATE_IDLE, RTIMER_SECOND / 100);
} /* idle(), 21.05.2015 */
/*---------------------------------------------------------------------------*/
@ -1922,7 +1894,7 @@ idle_calibrate_rx(void)
rf_flags &= ~RF_RX_PROCESSING_PKT;
strobe(CC1200_SFRX);
strobe(CC1200_SRX);
BUSYWAIT_UNTIL_STATE(STATE_RX, RTIMER_SECOND / 100);
RTIMER_BUSYWAIT_UNTIL_STATE(STATE_RX, RTIMER_SECOND / 100);
ENABLE_GPIO_INTERRUPTS();
@ -1947,7 +1919,7 @@ rx_rx(void)
strobe(CC1200_SFTX);
} else {
strobe(CC1200_SIDLE);
BUSYWAIT_UNTIL_STATE(STATE_IDLE,
RTIMER_BUSYWAIT_UNTIL_STATE(STATE_IDLE,
RTIMER_SECOND / 100);
}
@ -1959,7 +1931,7 @@ rx_rx(void)
strobe(CC1200_SFRX);
strobe(CC1200_SRX);
BUSYWAIT_UNTIL_STATE(STATE_RX, RTIMER_SECOND / 100);
RTIMER_BUSYWAIT_UNTIL_STATE(STATE_RX, RTIMER_SECOND / 100);
}
/*---------------------------------------------------------------------------*/
@ -2002,14 +1974,14 @@ idle_tx_rx(const uint8_t *payload, uint16_t payload_len)
#if USE_SFSTXON
/* Wait for synthesizer to be ready */
BUSYWAIT_UNTIL_STATE(STATE_FSTXON, RTIMER_SECOND / 100);
RTIMER_BUSYWAIT_UNTIL_STATE(STATE_FSTXON, RTIMER_SECOND / 100);
#endif
/* Start TX */
strobe(CC1200_STX);
/* Wait for TX to start. */
BUSYWAIT_UNTIL((cc1200_arch_gpio0_read_pin() == 1), RTIMER_SECOND / 100);
RTIMER_BUSYWAIT_UNTIL((cc1200_arch_gpio0_read_pin() == 1), RTIMER_SECOND / 100);
/* Turned off at the latest in idle() */
TX_LEDS_ON();
@ -2072,7 +2044,7 @@ idle_tx_rx(const uint8_t *payload, uint16_t payload_len)
*/
INFO("RF: TX failure!\n");
BUSYWAIT_UNTIL((state() != STATE_TX), RTIMER_SECOND / 100);
RTIMER_BUSYWAIT_UNTIL((state() != STATE_TX), RTIMER_SECOND / 100);
/* Re-configure GPIO2 */
single_write(CC1200_IOCFG2, GPIO2_IOCFG);
idle();
@ -2086,12 +2058,12 @@ idle_tx_rx(const uint8_t *payload, uint16_t payload_len)
} else {
/* Wait for TX to complete */
BUSYWAIT_UNTIL((cc1200_arch_gpio0_read_pin() == 0),
RTIMER_BUSYWAIT_UNTIL((cc1200_arch_gpio0_read_pin() == 0),
CC1200_RF_CFG.tx_pkt_lifetime);
}
#else
/* Wait for TX to complete */
BUSYWAIT_UNTIL((cc1200_arch_gpio0_read_pin() == 0),
RTIMER_BUSYWAIT_UNTIL((cc1200_arch_gpio0_read_pin() == 0),
CC1200_RF_CFG.tx_pkt_lifetime);
#endif

View File

@ -220,6 +220,18 @@
#endif /* #if SPI1_IN_USE */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name CC2538 TSCH configuration
*
* @{
*/
#define RADIO_PHY_OVERHEAD CC2538_PHY_OVERHEAD
#define RADIO_BYTE_AIR_TIME CC2538_BYTE_AIR_TIME
#define RADIO_DELAY_BEFORE_TX CC2538_DELAY_BEFORE_TX
#define RADIO_DELAY_BEFORE_RX CC2538_DELAY_BEFORE_RX
#define RADIO_DELAY_BEFORE_DETECT CC2538_DELAY_BEFORE_DETECT
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name Device string used on startup
* @{

View File

@ -30,8 +30,10 @@
*
*/
/* Dummy watchdog routines for the Raven 1284p */
/* Dummy watchdog routines for Cooja motes */
#include "dev/watchdog.h"
#include "lib/simEnvChange.h"
#include "sys/cooja_mt.h"
/*---------------------------------------------------------------------------*/
void
@ -47,6 +49,9 @@ watchdog_start(void)
void
watchdog_periodic(void)
{
/* Yield and give control back to the simulator scheduler */
simProcessRunValue = 1;
cooja_mt_yield();
}
/*---------------------------------------------------------------------------*/
void

View File

@ -130,13 +130,6 @@
#define MICROMAC_CONF_ALWAYS_ON 1
#endif /* MICROMAC_CONF_ALWAYS_ON */
#define BUSYWAIT_UNTIL(cond, max_time) \
do { \
rtimer_clock_t t0; \
t0 = RTIMER_NOW(); \
while(!(cond) && RTIMER_CLOCK_LT(RTIMER_NOW(), t0 + (max_time))) ; \
} while(0)
/* Local variables */
static volatile signed char radio_last_rssi;
static volatile uint8_t radio_last_correlation; /* LQI */
@ -377,14 +370,14 @@ transmit(unsigned short payload_len)
(send_on_cca ? E_MMAC_TX_USE_CCA : E_MMAC_TX_NO_CCA));
#endif
if(poll_mode) {
BUSYWAIT_UNTIL(u32MMAC_PollInterruptSource(E_MMAC_INT_TX_COMPLETE), MAX_PACKET_DURATION);
RTIMER_BUSYWAIT_UNTIL(u32MMAC_PollInterruptSource(E_MMAC_INT_TX_COMPLETE), MAX_PACKET_DURATION);
} else {
if(in_ack_transmission) {
/* as nested interupts are not possible, the tx flag will never be cleared */
BUSYWAIT_UNTIL(FALSE, MAX_ACK_DURATION);
RTIMER_BUSYWAIT_UNTIL(FALSE, MAX_ACK_DURATION);
} else {
/* wait until the tx flag is cleared */
BUSYWAIT_UNTIL(!tx_in_progress, MAX_PACKET_DURATION);
RTIMER_BUSYWAIT_UNTIL(!tx_in_progress, MAX_PACKET_DURATION);
}
}

View File

@ -66,14 +66,6 @@ extern volatile unsigned char xonxoff_state;
#endif /* UART_XONXOFF_FLOW_CTRL */
/*** Macro Definitions ***/
#define BUSYWAIT_UNTIL(cond, max_time) \
do { \
rtimer_clock_t t0; \
t0 = RTIMER_NOW(); \
while(!(cond) && RTIMER_CLOCK_LT(RTIMER_NOW(), t0 + (max_time))) ; \
} while(0)
#define DEBUG_UART_BUFFERED FALSE
#define CHAR_DEADLINE (uart_char_delay * 100)
@ -276,7 +268,7 @@ uart_driver_write_with_deadline(uint8_t uart_dev, uint8_t ch)
volatile int16_t write = 0;
watchdog_periodic();
/* wait until there is space in tx fifo */
BUSYWAIT_UNTIL(write = (uart_driver_get_tx_fifo_available_space(uart_dev) > 0),
RTIMER_BUSYWAIT_UNTIL(write = (uart_driver_get_tx_fifo_available_space(uart_dev) > 0),
CHAR_DEADLINE);
/* write only if there is space so we do not get stuck */
if(write) {

View File

@ -174,6 +174,18 @@
#define I2C_SDA_PIN 4
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name CC2538 TSCH configuration
*
* @{
*/
#define RADIO_PHY_OVERHEAD CC2538_PHY_OVERHEAD
#define RADIO_BYTE_AIR_TIME CC2538_BYTE_AIR_TIME
#define RADIO_DELAY_BEFORE_TX CC2538_DELAY_BEFORE_TX
#define RADIO_DELAY_BEFORE_RX CC2538_DELAY_BEFORE_RX
#define RADIO_DELAY_BEFORE_DETECT CC2538_DELAY_BEFORE_DETECT
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name Device string used on startup
* @{

View File

@ -8,9 +8,7 @@ ifndef CONTIKI
$(error 'CONTIKI' not defined! You must specify where CONTIKI resides!)
endif
ifndef BOARD
$(error 'BOARD' not defined! You must specify which board you are using!)
endif
BOARD ?= srf06/cc26x0
################################################################################
### Resolve the SimpleLink Family

View File

@ -63,9 +63,9 @@ LPM_MODULE(rf_switch_module, NULL, shutdown_handler, NULL, LPM_DOMAIN_NONE);
void
rf_switch_init()
{
ti_lib_rom_ioc_pin_type_gpio_output(POWER_PIN);
ti_lib_ioc_pin_type_gpio_output(POWER_PIN);
ti_lib_gpio_clear_dio(POWER_PIN);
ti_lib_rom_ioc_pin_type_gpio_output(SELECT_PIN);
ti_lib_ioc_pin_type_gpio_output(SELECT_PIN);
ti_lib_gpio_clear_dio(SELECT_PIN);
lpm_register_module(&rf_switch_module);

View File

@ -158,11 +158,11 @@ platform_init_stage_one()
* latches in the first place. Before doing these things though, we should
* allow software to first regain control of pins
*/
#if !defined(ThisLibraryIsFor_CC26x0R2_HaltIfViolated)
ti_lib_pwr_ctrl_io_freeze_disable();
ti_lib_aon_ioc_freeze_disable();
HWREG(AON_SYSCTL_BASE + AON_SYSCTL_O_SLEEPCTL) = 1;
ti_lib_sys_ctrl_aon_sync();
#endif
ti_lib_rom_int_enable(INT_AON_GPIO_EDGE);
ti_lib_int_enable(INT_AON_GPIO_EDGE);
ti_lib_int_master_enable();
soc_rtc_init();

View File

@ -601,11 +601,11 @@ configure(int type, int enable)
{
switch(type) {
case SENSORS_HW_INIT:
ti_lib_rom_ioc_pin_type_gpio_input(BOARD_IOID_MPU_INT);
ti_lib_ioc_pin_type_gpio_input(BOARD_IOID_MPU_INT);
ti_lib_ioc_io_port_pull_set(BOARD_IOID_MPU_INT, IOC_IOPULL_DOWN);
ti_lib_ioc_io_hyst_set(BOARD_IOID_MPU_INT, IOC_HYST_ENABLE);
ti_lib_rom_ioc_pin_type_gpio_output(BOARD_IOID_MPU_POWER);
ti_lib_ioc_pin_type_gpio_output(BOARD_IOID_MPU_POWER);
ti_lib_ioc_io_drv_strength_set(BOARD_IOID_MPU_POWER, IOC_CURRENT_4MA,
IOC_STRENGTH_MAX);
ti_lib_gpio_clear_dio(BOARD_IOID_MPU_POWER);

View File

@ -59,10 +59,10 @@ config(int type, int enable)
ti_lib_ioc_pin_type_gpio_output(BOARD_IOID_ALS_PWR);
break;
case SENSORS_ACTIVE:
ti_lib_rom_ioc_pin_type_gpio_output(BOARD_IOID_ALS_PWR);
ti_lib_rom_ioc_port_configure_set(BOARD_IOID_ALS_OUT, IOC_PORT_GPIO,
IOC_STD_OUTPUT);
ti_lib_rom_ioc_pin_type_gpio_input(BOARD_IOID_ALS_OUT);
ti_lib_ioc_pin_type_gpio_output(BOARD_IOID_ALS_PWR);
ti_lib_ioc_port_configure_set(BOARD_IOID_ALS_OUT, IOC_PORT_GPIO,
IOC_STD_OUTPUT);
ti_lib_ioc_pin_type_gpio_input(BOARD_IOID_ALS_OUT);
if(enable) {
ti_lib_gpio_set_dio(BOARD_IOID_ALS_PWR);

View File

@ -46,23 +46,8 @@ MODULES += arch/dev/cc1200 arch/dev/rgb-led os/storage/cfs
BSL = $(CONTIKI)/tools/cc2538-bsl/cc2538-bsl.py
### Use the specific Zoul subplatform to query for connected devices
ifdef MOTELIST_ZOLERTIA
MOTELIST_FLAGS += -b $(MOTELIST_ZOLERTIA)
endif
### Detect if a mote is connected over serial port
ifeq ($(HOST_OS),Darwin)
USBDEVPREFIX=
MOTELIST := $(CONTIKI)/tools/zolertia/motelist-zolertia-macos
MOTES := $(shell $(MOTELIST) -c 2>&- | cut -f 2 -d ,)
else
### If we are not running under Mac, we assume Linux
USBDEVPREFIX=
MOTELIST := $(CONTIKI)/tools/zolertia/motelist-zolertia
MOTES := $(shell $(MOTELIST) -b $(MOTELIST_ZOLERTIA) -c 2>&- | cut -f 2 -d , | \
perl -ne 'print $$1 . " " if(m-(/dev/\w+)-);')
endif
MOTES := $(shell python $(TOOLS_DIR)/motelist/motelist.py --omit-header \
| grep $(MOTELIST_ZOLERTIA) | cut -f1 -d " ")
### If PORT is defined, override to keep backward compatibility
ifdef PORT
@ -81,7 +66,8 @@ endif
### Variable that expands into a pattern rule to upload to a given MOTE.
### Requires $(MOTE) to be defined
### $$$$ Double escapes $s that need to be passed to the shell - once for when make parses UPLOAD_RULE, and once for when the expanded rule is parsed by make.
### $$$$ Double escapes $s that need to be passed to the shell - once for when
### make parses UPLOAD_RULE, and once for when the expanded rule is parsed by make.
define UPLOAD_RULE
%.$(MOTE): %.bin %.elf
@echo "Flashing $(MOTE)"
@ -94,10 +80,8 @@ endef
### Create an upload rule for every MOTE connected
$(foreach MOTE,$(MOTES),$(eval $(UPLOAD_RULE)))
motelist:
$(MOTELIST)
zoul-motelist:
$(MOTELIST) $(MOTELIST_FLAGS)
.PHONY: zoul-motes
zoul-motes:
@echo $(MOTES)

View File

@ -76,18 +76,8 @@
/*---------------------------------------------------------------------------*/
#if DEBUG_CC1200_ARCH > 0
#define PRINTF(...) printf(__VA_ARGS__)
#define BUSYWAIT_UNTIL(cond, max_time) \
do { \
rtimer_clock_t t0; \
t0 = RTIMER_NOW(); \
while(!(cond) && RTIMER_CLOCK_LT(RTIMER_NOW(), t0 + (max_time))) {} \
if(!(RTIMER_CLOCK_LT(RTIMER_NOW(), t0 + (max_time)))) { \
printf("ARCH: Timeout exceeded in line %d!\n", __LINE__); \
} \
} while(0)
#else
#define PRINTF(...)
#define BUSYWAIT_UNTIL(cond, max_time) while(!cond)
#endif
/*---------------------------------------------------------------------------*/
extern int cc1200_rx_interrupt(void);
@ -105,7 +95,7 @@ cc1200_arch_spi_select(void)
/* Set CSn to low (0) */
GPIO_CLR_PIN(CC1200_SPI_CSN_PORT_BASE, CC1200_SPI_CSN_PIN_MASK);
/* The MISO pin should go low before chip is fully enabled. */
BUSYWAIT_UNTIL(
RTIMER_BUSYWAIT_UNTIL(
GPIO_READ_PIN(CC1200_SPI_MISO_PORT_BASE, CC1200_SPI_MISO_PIN_MASK) == 0,
RTIMER_SECOND / 100);
}
@ -288,7 +278,7 @@ cc1200_arch_init(void)
cc1200_arch_spi_deselect();
/* Ensure MISO is high */
BUSYWAIT_UNTIL(
RTIMER_BUSYWAIT_UNTIL(
GPIO_READ_PIN(CC1200_SPI_MISO_PORT_BASE, CC1200_SPI_MISO_PIN_MASK),
RTIMER_SECOND / 10);
}
@ -297,4 +287,3 @@ cc1200_arch_init(void)
* @}
* @}
*/

View File

@ -51,15 +51,6 @@
#define PRINTF(...)
#endif
/*---------------------------------------------------------------------------*/
#define BUSYWAIT_UNTIL(max_time) \
do { \
rtimer_clock_t t0; \
t0 = RTIMER_NOW(); \
while(RTIMER_CLOCK_LT(RTIMER_NOW(), t0 + (max_time))) { \
watchdog_periodic(); \
} \
} while(0)
/*---------------------------------------------------------------------------*/
#define DHT22_PORT_BASE GPIO_PORT_TO_BASE(DHT22_PORT)
#define DHT22_PIN_MASK GPIO_PIN_MASK(DHT22_PIN)
/*---------------------------------------------------------------------------*/
@ -80,12 +71,12 @@ dht22_read(void)
/* Exit low power mode and initialize variables */
GPIO_SET_OUTPUT(DHT22_PORT_BASE, DHT22_PIN_MASK);
GPIO_SET_PIN(DHT22_PORT_BASE, DHT22_PIN_MASK);
BUSYWAIT_UNTIL(DHT22_AWAKE_TIME);
RTIMER_BUSYWAIT(DHT22_AWAKE_TIME);
memset(dht22_data, 0, DHT22_BUFFER);
/* Initialization sequence */
GPIO_CLR_PIN(DHT22_PORT_BASE, DHT22_PIN_MASK);
BUSYWAIT_UNTIL(DHT22_START_TIME);
RTIMER_BUSYWAIT(DHT22_START_TIME);
GPIO_SET_PIN(DHT22_PORT_BASE, DHT22_PIN_MASK);
clock_delay_usec(DHT22_READY_TIME);

View File

@ -1,2 +1,2 @@
MOTELIST_ZOLERTIA = firefly
MOTELIST_ZOLERTIA := Firefly
BOARD_SOURCEFILES += board.c

View File

@ -1,2 +1,2 @@
MOTELIST_ZOLERTIA = firefly
MOTELIST_ZOLERTIA := Firefly
BOARD_SOURCEFILES += board.c

View File

@ -1,4 +1,4 @@
MOTELIST_ZOLERTIA = orion
MOTELIST_ZOLERTIA := Orion
MODULES += arch/dev/enc28j60
CC2538_ENC28J60_ARCH ?= gpio
ifeq ($(WITH_IP64),1)

View File

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

View File

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

View File

@ -2,7 +2,6 @@ CONTIKI_PROJECT = sixp-node
PROJECT_SOURCEFILES += test-sf.c
PLATFORMS_EXCLUDE = sky nrf52dk native simplelink
BOARDS_EXCLUDE = srf06/cc13xx launchpad/cc1310 launchpad/cc1350 sensortag/cc2650 sensortag/cc1350
CONTIKI = ../../../

View File

@ -2,7 +2,7 @@ CONTIKI_PROJECT = node
all: $(CONTIKI_PROJECT)
PLATFORMS_EXCLUDE = sky nrf52dk native simplelink
BOARDS_EXCLUDE = srf06/cc13xx launchpad/cc1310 launchpad/cc1350 sensortag/cc2650 sensortag/cc1350
BOARDS_EXCLUDE = sensortag/cc2650 sensortag/cc1350
MAKE_WITH_SECURITY ?= 0 # force Security from command line
ifeq ($(MAKE_WITH_SECURITY),1)

View File

@ -2,7 +2,6 @@ CONTIKI_PROJECT = node
all: $(CONTIKI_PROJECT)
PLATFORMS_EXCLUDE = sky nrf52dk native simplelink
BOARDS_EXCLUDE = srf06/cc13xx launchpad/cc1310 launchpad/cc1350 sensortag/cc2650 sensortag/cc1350
CONTIKI=../../..

View File

@ -2,7 +2,6 @@ CONTIKI_PROJECT = node-sixtop
all: $(CONTIKI_PROJECT)
PLATFORMS_EXCLUDE = sky nrf52dk native simplelink
BOARDS_EXCLUDE = srf06/cc13xx launchpad/cc1310 launchpad/cc1350 sensortag/cc2650 sensortag/cc1350
PROJECT_SOURCEFILES += sf-simple.c
CONTIKI=../../..

View File

@ -79,7 +79,7 @@ PROCESS_THREAD(timer_process, ev, data)
PROCESS_BEGIN();
ctimer_set(&timer_ctimer, CLOCK_SECOND, ctimer_callback, NULL);
rtimer_set(&timer_rtimer, RTIMER_NOW() + CLOCK_SECOND / 2, 0,
rtimer_set(&timer_rtimer, RTIMER_NOW() + RTIMER_SECOND / 2, 0,
rtimer_callback, NULL);
while(1) {

View File

@ -119,7 +119,7 @@
/*---------------------------------------------------------------------------*/
/* Default configuration values */
#define CC26XX_WEB_DEMO_DEFAULT_ORG_ID "quickstart"
#if CPU_FAMILY_CC13XX
#if CPU_FAMILY_CC13X0
#define CC26XX_WEB_DEMO_DEFAULT_TYPE_ID "cc13xx"
#else
#define CC26XX_WEB_DEMO_DEFAULT_TYPE_ID "cc26xx"

View File

@ -67,13 +67,21 @@ spi_release(const spi_device_t *dev)
spi_status_t
spi_select(const spi_device_t *dev)
{
return spi_arch_select(dev);
if(!spi_arch_has_lock(dev)) {
return SPI_DEV_STATUS_BUS_NOT_OWNED;
}
gpio_hal_arch_clear_pin(dev->pin_spi_cs);
return SPI_DEV_STATUS_OK;
}
/*---------------------------------------------------------------------------*/
spi_status_t
spi_deselect(const spi_device_t *dev)
{
return spi_arch_deselect(dev);
gpio_hal_arch_set_pin(dev->pin_spi_cs);
return SPI_DEV_STATUS_OK;
}
/*---------------------------------------------------------------------------*/
bool

View File

@ -323,25 +323,6 @@ spi_status_t spi_arch_transfer(const spi_device_t *dev,
uint8_t *buf, int rlen,
int ignore_len);
/**
* \brief Selects an SPI device
* \param dev An SPI device configuration that specifies the CS pin.
* \return SPI return code
*
* Clears the CS pin. It should work only if the device has already
* locked the SPI controller.
*/
spi_status_t spi_arch_select(const spi_device_t *dev);
/**
* \brief Deselects an SPI device
* \param dev An SPI device configuration that specifies the CS pin.
* \return SPI return code
*
* Set the CS pin. Locking the SPI controller is not needed.
*/
spi_status_t spi_arch_deselect(const spi_device_t *dev);
#endif /* SPI_H_ */
/*---------------------------------------------------------------------------*/
/**

View File

@ -872,6 +872,7 @@ parse_publish_vhdr(struct mqtt_connection *conn,
/* Read out topic length */
if(conn->in_packet.topic_len_received == 0) {
conn->in_packet.topic_pos = 0;
conn->in_packet.topic_len = (input_data_ptr[(*pos)++] << 8);
conn->in_packet.byte_counter++;
if(*pos >= input_data_len) {
@ -880,7 +881,11 @@ parse_publish_vhdr(struct mqtt_connection *conn,
conn->in_packet.topic_len |= input_data_ptr[(*pos)++];
conn->in_packet.byte_counter++;
conn->in_packet.topic_len_received = 1;
/* Abort if topic is longer than our topic buffer */
if(conn->in_packet.topic_len > MQTT_MAX_TOPIC_LENGTH) {
DBG("MQTT - topic too long %u/%u\n", conn->in_packet.topic_len, MQTT_MAX_TOPIC_LENGTH);
return;
}
DBG("MQTT - Read PUBLISH topic len %i\n", conn->in_packet.topic_len);
/* WARNING: Check here if TOPIC fits in payload area, otherwise error */
}

View File

@ -37,12 +37,10 @@
#include "net/link-stats.h"
#include <stdio.h>
#define DEBUG 0
#if DEBUG
#define PRINTF(...) printf(__VA_ARGS__)
#else
#define PRINTF(...)
#endif
/* Log configuration */
#include "sys/log.h"
#define LOG_MODULE "Link Stats"
#define LOG_LEVEL LOG_LEVEL_MAC
/* Maximum value for the Tx count counter */
#define TX_COUNT_MAX 32
@ -82,6 +80,13 @@ link_stats_from_lladdr(const linkaddr_t *lladdr)
return nbr_table_get_from_lladdr(link_stats, lladdr);
}
/*---------------------------------------------------------------------------*/
/* Returns the neighbor's address given a link stats item */
const linkaddr_t *
link_stats_get_lladdr(const struct link_stats *stat)
{
return nbr_table_get_lladdr(link_stats, stat);
}
/*---------------------------------------------------------------------------*/
/* Are the statistics fresh? */
int
link_stats_is_fresh(const struct link_stats *stats)
@ -156,6 +161,14 @@ link_stats_packet_sent(const linkaddr_t *lladdr, int status, int numtx)
stats->last_tx_time = clock_time();
stats->freshness = MIN(stats->freshness + numtx, FRESHNESS_MAX);
#if LINK_STATS_PACKET_COUNTERS
/* Update paket counters */
stats->cnt_current.num_packets_tx += numtx;
if(status == MAC_TX_OK) {
stats->cnt_current.num_packets_acked++;
}
#endif
/* Add penalty in case of no-ACK */
if(status == MAC_TX_NOACK) {
numtx += ETX_NOACK_PENALTY;
@ -219,8 +232,38 @@ link_stats_input_callback(const linkaddr_t *lladdr)
/* Update RSSI EWMA */
stats->rssi = ((int32_t)stats->rssi * (EWMA_SCALE - EWMA_ALPHA) +
(int32_t)packet_rssi * EWMA_ALPHA) / EWMA_SCALE;
#if LINK_STATS_PACKET_COUNTERS
stats->cnt_current.num_packets_rx++;
#endif
}
/*---------------------------------------------------------------------------*/
#if LINK_STATS_PACKET_COUNTERS
/*---------------------------------------------------------------------------*/
static void
print_and_update_counters(void)
{
struct link_stats *stats;
for(stats = nbr_table_head(link_stats); stats != NULL;
stats = nbr_table_next(link_stats, stats)) {
struct link_packet_counter *c = &stats->cnt_current;
LOG_INFO("num packets: tx=%u ack=%u rx=%u to=",
c->num_packets_tx, c->num_packets_acked, c->num_packets_rx);
LOG_INFO_LLADDR(link_stats_get_lladdr(stats));
LOG_INFO_("\n");
stats->cnt_total.num_packets_tx += stats->cnt_current.num_packets_tx;
stats->cnt_total.num_packets_acked += stats->cnt_current.num_packets_acked;
stats->cnt_total.num_packets_rx += stats->cnt_current.num_packets_rx;
memset(&stats->cnt_current, 0, sizeof(stats->cnt_current));
}
}
/*---------------------------------------------------------------------------*/
#endif /* LINK_STATS_PACKET_COUNTERS */
/*---------------------------------------------------------------------------*/
/* Periodic timer called at a period of FRESHNESS_HALF_LIFE */
static void
periodic(void *ptr)
@ -231,6 +274,10 @@ periodic(void *ptr)
for(stats = nbr_table_head(link_stats); stats != NULL; stats = nbr_table_next(link_stats, stats)) {
stats->freshness >>= 1;
}
#if LINK_STATS_PACKET_COUNTERS
print_and_update_counters();
#endif
}
/*---------------------------------------------------------------------------*/
/* Resets link-stats module */

View File

@ -56,6 +56,25 @@
#define LINK_STATS_ETX_FROM_PACKET_COUNT 0
#endif /* LINK_STATS_ETX_FROM_PACKET_COUNT */
/* Store and periodically print packet counters? */
#ifdef LINK_STATS_CONF_PACKET_COUNTERS
#define LINK_STATS_PACKET_COUNTERS LINK_STATS_CONF_PACKET_COUNTERS
#else /* LINK_STATS_CONF_PACKET_COUNTERS */
#define LINK_STATS_PACKET_COUNTERS 0
#endif /* LINK_STATS_PACKET_COUNTERS */
typedef uint16_t link_packet_stat_t;
struct link_packet_counter {
/* total attempts to transmit unicast packets */
link_packet_stat_t num_packets_tx;
/* total ACKs for unicast packets */
link_packet_stat_t num_packets_acked;
/* total number of unicast and broadcast packets received */
link_packet_stat_t num_packets_rx;
};
/* All statistics of a given link */
struct link_stats {
clock_time_t last_tx_time; /* Last Tx timestamp */
@ -66,10 +85,17 @@ struct link_stats {
uint8_t tx_count; /* Tx count, used for ETX calculation */
uint8_t ack_count; /* ACK count, used for ETX calculation */
#endif /* LINK_STATS_ETX_FROM_PACKET_COUNT */
#if LINK_STATS_PACKET_COUNTERS
struct link_packet_counter cnt_current; /* packets in the current period */
struct link_packet_counter cnt_total; /* packets in total */
#endif
};
/* Returns the neighbor's link statistics */
const struct link_stats *link_stats_from_lladdr(const linkaddr_t *lladdr);
/* Returns the address of the neighbor */
const linkaddr_t *link_stats_get_lladdr(const struct link_stats *);
/* Are the statistics fresh? */
int link_stats_is_fresh(const struct link_stats *stats);
/* Resets link-stats module */

View File

@ -50,11 +50,6 @@
#include "lib/list.h"
#include "lib/memb.h"
#if CONTIKI_TARGET_COOJA
#include "lib/simEnvChange.h"
#include "sys/cooja_mt.h"
#endif /* CONTIKI_TARGET_COOJA */
/* Log configuration */
#include "sys/log.h"
#define LOG_MODULE "CSMA"
@ -201,17 +196,10 @@ send_one_packet(void *ptr)
if(is_broadcast) {
ret = MAC_TX_OK;
} else {
rtimer_clock_t wt;
/* Check for ack */
wt = RTIMER_NOW();
watchdog_periodic();
while(RTIMER_CLOCK_LT(RTIMER_NOW(), wt + CSMA_ACK_WAIT_TIME)) {
#if CONTIKI_TARGET_COOJA
simProcessRunValue = 1;
cooja_mt_yield();
#endif /* CONTIKI_TARGET_COOJA */
}
/* Wait for max CSMA_ACK_WAIT_TIME */
RTIMER_BUSYWAIT_UNTIL(NETSTACK_RADIO.pending_packet(), CSMA_ACK_WAIT_TIME);
ret = MAC_TX_NOACK;
if(NETSTACK_RADIO.receiving_packet() ||
@ -220,17 +208,8 @@ send_one_packet(void *ptr)
int len;
uint8_t ackbuf[CSMA_ACK_LEN];
if(CSMA_AFTER_ACK_DETECTED_WAIT_TIME > 0) {
wt = RTIMER_NOW();
watchdog_periodic();
while(RTIMER_CLOCK_LT(RTIMER_NOW(),
wt + CSMA_AFTER_ACK_DETECTED_WAIT_TIME)) {
#if CONTIKI_TARGET_COOJA
simProcessRunValue = 1;
cooja_mt_yield();
#endif /* CONTIKI_TARGET_COOJA */
}
}
/* Wait an additional CSMA_AFTER_ACK_DETECTED_WAIT_TIME to complete reception */
RTIMER_BUSYWAIT_UNTIL(NETSTACK_RADIO.pending_packet(), CSMA_AFTER_ACK_DETECTED_WAIT_TIME);
if(NETSTACK_RADIO.pending_packet()) {
len = NETSTACK_RADIO.read(ackbuf, CSMA_ACK_LEN);

View File

@ -77,9 +77,7 @@
/* The approximate number of slots per second */
#define TSCH_SLOTS_PER_SECOND (1000000 / tsch_timing_us[tsch_ts_timeslot_length])
/* Calculate packet tx/rx duration in rtimer ticks based on sent
* packet len in bytes with 802.15.4 250kbps data rate.
* One byte = 32us. Add two bytes for CRC and one for len field */
/* Calculate packet tx/rx duration in rtimer ticks based on packet length in bytes. */
#define TSCH_PACKET_DURATION(len) US_TO_RTIMERTICKS(RADIO_BYTE_AIR_TIME * ((len) + RADIO_PHY_OVERHEAD))
/* Convert rtimer ticks to clock and vice versa */

View File

@ -52,10 +52,6 @@
#include "net/queuebuf.h"
#include "net/mac/framer/framer-802154.h"
#include "net/mac/tsch/tsch.h"
#if CONTIKI_TARGET_COOJA
#include "lib/simEnvChange.h"
#include "sys/cooja_mt.h"
#endif /* CONTIKI_TARGET_COOJA */
#include "sys/log.h"
/* TSCH debug macros, i.e. to set LEDs or GPIOs on various TSCH
@ -206,10 +202,7 @@ tsch_get_lock(void)
busy_wait = 1;
busy_wait_time = RTIMER_NOW();
while(tsch_in_slot_operation) {
#if CONTIKI_TARGET_COOJA
simProcessRunValue = 1;
cooja_mt_yield();
#endif /* CONTIKI_TARGET_COOJA */
watchdog_periodic();
}
busy_wait_time = RTIMER_NOW() - busy_wait_time;
}
@ -303,7 +296,7 @@ tsch_schedule_slot_operation(struct rtimer *tm, rtimer_clock_t ref_time, rtimer_
}
/* block until the time to schedule comes */
BUSYWAIT_UNTIL_ABS(0, ref_time, offset);
RTIMER_BUSYWAIT_UNTIL_ABS(0, ref_time, offset);
return 0;
}
/*---------------------------------------------------------------------------*/
@ -314,7 +307,7 @@ tsch_schedule_slot_operation(struct rtimer *tm, rtimer_clock_t ref_time, rtimer_
do { \
if(tsch_schedule_slot_operation(tm, ref_time, offset - RTIMER_GUARD, str)) { \
PT_YIELD(pt); \
BUSYWAIT_UNTIL_ABS(0, ref_time, offset); \
RTIMER_BUSYWAIT_UNTIL_ABS(0, ref_time, offset); \
} \
} while(0);
/*---------------------------------------------------------------------------*/
@ -514,7 +507,7 @@ PT_THREAD(tsch_tx_slot(struct pt *pt, struct rtimer *t))
TSCH_DEBUG_TX_EVENT();
tsch_radio_on(TSCH_RADIO_CMD_ON_WITHIN_TIMESLOT);
/* CCA */
BUSYWAIT_UNTIL_ABS(!(cca_status &= NETSTACK_RADIO.channel_clear()),
RTIMER_BUSYWAIT_UNTIL_ABS(!(cca_status &= NETSTACK_RADIO.channel_clear()),
current_slot_start, tsch_timing[tsch_ts_cca_offset] + tsch_timing[tsch_ts_cca]);
TSCH_DEBUG_TX_EVENT();
/* there is not enough time to turn radio off */
@ -561,14 +554,14 @@ PT_THREAD(tsch_tx_slot(struct pt *pt, struct rtimer *t))
TSCH_DEBUG_TX_EVENT();
tsch_radio_on(TSCH_RADIO_CMD_ON_WITHIN_TIMESLOT);
/* Wait for ACK to come */
BUSYWAIT_UNTIL_ABS(NETSTACK_RADIO.receiving_packet(),
RTIMER_BUSYWAIT_UNTIL_ABS(NETSTACK_RADIO.receiving_packet(),
tx_start_time, tx_duration + tsch_timing[tsch_ts_rx_ack_delay] + tsch_timing[tsch_ts_ack_wait] + RADIO_DELAY_BEFORE_DETECT);
TSCH_DEBUG_TX_EVENT();
ack_start_time = RTIMER_NOW() - RADIO_DELAY_BEFORE_DETECT;
/* Wait for ACK to finish */
BUSYWAIT_UNTIL_ABS(!NETSTACK_RADIO.receiving_packet(),
RTIMER_BUSYWAIT_UNTIL_ABS(!NETSTACK_RADIO.receiving_packet(),
ack_start_time, tsch_timing[tsch_ts_max_ack]);
TSCH_DEBUG_TX_EVENT();
tsch_radio_off(TSCH_RADIO_CMD_OFF_WITHIN_TIMESLOT);
@ -748,7 +741,7 @@ PT_THREAD(tsch_rx_slot(struct pt *pt, struct rtimer *t))
packet_seen = NETSTACK_RADIO.receiving_packet() || NETSTACK_RADIO.pending_packet();
if(!packet_seen) {
/* Check if receiving within guard time */
BUSYWAIT_UNTIL_ABS((packet_seen = NETSTACK_RADIO.receiving_packet()),
RTIMER_BUSYWAIT_UNTIL_ABS((packet_seen = NETSTACK_RADIO.receiving_packet()),
current_slot_start, tsch_timing[tsch_ts_rx_offset] + tsch_timing[tsch_ts_rx_wait] + RADIO_DELAY_BEFORE_DETECT);
}
if(!packet_seen) {
@ -760,7 +753,7 @@ PT_THREAD(tsch_rx_slot(struct pt *pt, struct rtimer *t))
rx_start_time = RTIMER_NOW() - RADIO_DELAY_BEFORE_DETECT;
/* Wait until packet is received, turn radio off */
BUSYWAIT_UNTIL_ABS(!NETSTACK_RADIO.receiving_packet(),
RTIMER_BUSYWAIT_UNTIL_ABS(!NETSTACK_RADIO.receiving_packet(),
current_slot_start, tsch_timing[tsch_ts_rx_offset] + tsch_timing[tsch_ts_rx_wait] + tsch_timing[tsch_ts_max_tx]);
TSCH_DEBUG_RX_EVENT();
tsch_radio_off(TSCH_RADIO_CMD_OFF_WITHIN_TIMESLOT);

View File

@ -737,7 +737,7 @@ PT_THREAD(tsch_scan(struct pt *pt))
if(!is_packet_pending && NETSTACK_RADIO.receiving_packet()) {
/* If we are currently receiving a packet, wait until end of reception */
t0 = RTIMER_NOW();
BUSYWAIT_UNTIL_ABS((is_packet_pending = NETSTACK_RADIO.pending_packet()), t0, RTIMER_SECOND / 100);
RTIMER_BUSYWAIT_UNTIL_ABS((is_packet_pending = NETSTACK_RADIO.pending_packet()), t0, RTIMER_SECOND / 100);
}
if(is_packet_pending) {

View File

@ -65,30 +65,12 @@ frequency hopping for enhanced reliability.
#include "net/mac/tsch/tsch-rpl.h"
#endif /* UIP_CONF_IPV6_RPL */
#if CONTIKI_TARGET_COOJA
#include "lib/simEnvChange.h"
#include "sys/cooja_mt.h"
#endif /* CONTIKI_TARGET_COOJA */
/* Include Arch-Specific conf */
#ifdef TSCH_CONF_ARCH_HDR_PATH
#include TSCH_CONF_ARCH_HDR_PATH
#endif /* TSCH_CONF_ARCH_HDR_PATH */
/*********** Macros *********/
/* Wait for a condition with timeout t0+offset. */
#if CONTIKI_TARGET_COOJA
#define BUSYWAIT_UNTIL_ABS(cond, t0, offset) \
while(!(cond) && RTIMER_CLOCK_LT(RTIMER_NOW(), (t0) + (offset))) { \
simProcessRunValue = 1; \
cooja_mt_yield(); \
};
#else
#define BUSYWAIT_UNTIL_ABS(cond, t0, offset) \
while(!(cond) && RTIMER_CLOCK_LT(RTIMER_NOW(), (t0) + (offset))) ;
#endif /* CONTIKI_TARGET_COOJA */
/*********** Callbacks *********/
/* Link callbacks to RPL in case RPL is enabled */
@ -176,7 +158,7 @@ extern uint8_t tsch_current_channel;
extern uint8_t tsch_hopping_sequence[TSCH_HOPPING_SEQUENCE_MAX_LEN];
extern struct tsch_asn_divisor_t tsch_hopping_sequence_length;
/* TSCH timeslot timing (in micro-second) */
uint16_t tsch_timing_us[tsch_ts_elements_count];
extern uint16_t tsch_timing_us[tsch_ts_elements_count];
/* TSCH timeslot timing (in rtimer ticks) */
extern rtimer_clock_t tsch_timing[tsch_ts_elements_count];
/* Statistics on the current session */

View File

@ -272,7 +272,7 @@
#ifdef RPL_CONF_DAG_LIFETIME
#define RPL_DAG_LIFETIME RPL_CONF_DAG_LIFETIME
#else
#define RPL_DAG_LIFETIME (60 * 60) /* one hour */
#define RPL_DAG_LIFETIME (8 * 60) /* 8 hours */
#endif /* RPL_CONF_DAG_LIFETIME */
/*

View File

@ -76,7 +76,8 @@ struct ctimer {
* is the exact time that the callback timer last
* expired. Therefore, this function will cause the timer
* to be stable over time, unlike the ctimer_restart()
* function.
* function. If this is executed before the timer expired,
* this function has no effect.
*
* \sa ctimer_restart()
*/

View File

@ -107,7 +107,8 @@ void etimer_set(struct etimer *et, clock_time_t interval);
* is the exact time that the event timer last
* expired. Therefore, this function will cause the timer
* to be stable over time, unlike the etimer_restart()
* function.
* function. If this is executed before the timer expired,
* this function has no effect.
*
* \sa etimer_restart()
*/

View File

@ -54,6 +54,8 @@
#define RTIMER_H_
#include "contiki.h"
#include "dev/watchdog.h"
#include <stdbool.h>
/** \brief The rtimer size (in bytes) */
#ifdef RTIMER_CONF_CLOCK_SIZE
@ -186,6 +188,26 @@ void rtimer_arch_schedule(rtimer_clock_t t);
#define RTIMER_GUARD_TIME (RTIMER_ARCH_SECOND >> 14)
#endif /* RTIMER_CONF_GUARD_TIME */
/** \brief Busy-wait until a condition. Start time is t0, max wait time is max_time */
#define RTIMER_BUSYWAIT_UNTIL_ABS(cond, t0, max_time) \
({ \
bool c; \
while(!(c = cond) && RTIMER_CLOCK_LT(RTIMER_NOW(), (t0) + (max_time))) { \
watchdog_periodic(); \
} \
c; \
})
/** \brief Busy-wait until a condition for at most max_time */
#define RTIMER_BUSYWAIT_UNTIL(cond, max_time) \
({ \
rtimer_clock_t t0 = RTIMER_NOW(); \
RTIMER_BUSYWAIT_UNTIL_ABS(cond, t0, max_time); \
})
/** \brief Busy-wait for a fixed duration */
#define RTIMER_BUSYWAIT(duration) RTIMER_BUSYWAIT_UNTIL(0, duration)
#endif /* RTIMER_H_ */
/** @} */

View File

@ -77,7 +77,8 @@ stimer_set(struct stimer *t, unsigned long interval)
* given to the stimer_set() function. The start point of the interval
* is the exact time that the timer last expired. Therefore, this
* function will cause the timer to be stable over time, unlike the
* stimer_restart() function.
* stimer_restart() function. If this is executed before the
* timer expired, this function has no effect.
*
* \param t A pointer to the timer.
*
@ -86,7 +87,9 @@ stimer_set(struct stimer *t, unsigned long interval)
void
stimer_reset(struct stimer *t)
{
t->start += t->interval;
if(stimer_expired(t)) {
t->start += t->interval;
}
}
/*---------------------------------------------------------------------------*/
/**

View File

@ -74,9 +74,8 @@ timer_set(struct timer *t, clock_time_t interval)
* given to the timer_set() function. The start point of the interval
* is the exact time that the timer last expired. Therefore, this
* function will cause the timer to be stable over time, unlike the
* timer_restart() function.
*
* \note Must not be executed before timer expired
* timer_restart() function. If this is executed before the
* timer expired, this function has no effect.
*
* \param t A pointer to the timer.
* \sa timer_restart()
@ -84,7 +83,9 @@ timer_set(struct timer *t, clock_time_t interval)
void
timer_reset(struct timer *t)
{
t->start += t->interval;
if(timer_expired(t)) {
t->start += t->interval;
}
}
/*---------------------------------------------------------------------------*/
/**

View File

@ -16,7 +16,7 @@ libs/stack-check/sky \
lwm2m-ipso-objects/native \
lwm2m-ipso-objects/native:MAKE_WITH_DTLS=1 \
lwm2m-ipso-objects/native:DEFINES=LWM2M_Q_MODE_CONF_ENABLED=1 \
lwm2m-ipso-objects/native:DEFINES=LWM2M_Q_MODE_CONF_ENABLED=1,LWM2M_Q_MODE_CONF_INCLUDE_DYNAMIC_ADAPTATION=1\
lwm2m-ipso-objects/native:DEFINES=LWM2M_Q_MODE_CONF_ENABLED=1,LWM2M_Q_MODE_CONF_INCLUDE_DYNAMIC_ADAPTATION=1 \
rpl-udp/sky \
rpl-border-router/native \
rpl-border-router/native:MAKE_ROUTING=MAKE_ROUTING_RPL_CLASSIC \
@ -24,6 +24,8 @@ rpl-border-router/sky \
slip-radio/sky \
libs/ipv6-hooks/sky \
nullnet/native \
nullnet/sky \
nullnet/sky:MAKE_MAC=MAKE_MAC_TSCH \
mqtt-client/native \
coap/coap-example-client/native \
coap/coap-example-server/native \

View File

@ -80,7 +80,6 @@ coap/coap-example-server/cc2538dk \
slip-radio/cc2538dk \
lwm2m-ipso-objects/cc2538dk \
lwm2m-ipso-objects/cc2538dk:DEFINES=LWM2M_Q_MODE_CONF_ENABLED=1 \
lwm2m-ipso-objects/native:DEFINES=LWM2M_Q_MODE_CONF_ENABLED=1,LWM2M_Q_MODE_CONF_INCLUDE_DYNAMIC_ADAPTATION=1\
multicast/cc2538dk \
dev/gpio-hal/cc2538dk \
dev/leds/cc2538dk \
@ -90,6 +89,8 @@ platform-specific/cc2538-common/pka/cc2538dk \
hello-world/cc2538dk \
rpl-border-router/cc2538dk \
rpl-border-router/cc2538dk:MAKE_ROUTING=MAKE_ROUTING_RPL_CLASSIC \
6tisch/simple-node/cc2538dk \
6tisch/simple-node/cc2538dk:MAKE_WITH_SECURITY=1,MAKE_WITH_ORCHESTRA=1 \
hello-world/nrf52dk \
platform-specific/nrf52dk/coap-demo/coap-server/nrf52dk \
platform-specific/nrf52dk/coap-demo/coap-client/nrf52dk:SERVER_IPV6_EP=ffff \

View File

@ -28,6 +28,7 @@ storage/antelope-shell/zoul \
6tisch/simple-node/zoul:MAKE_WITH_ORCHESTRA=1 \
6tisch/simple-node/zoul:MAKE_WITH_SECURITY=1 \
libs/logging/zoul \
libs/logging/zoul:MAKE_MAC=MAKE_MAC_TSCH \
6tisch/etsi-plugtest-2017/zoul:BOARD=remote \
6tisch/6p-packet/zoul \
6tisch/sixtop/zoul \
@ -68,6 +69,8 @@ libs/ipv6-hooks/openmote-cc2538 \
libs/shell/openmote-cc2538 \
libs/simple-energest/openmote-cc2538 \
libs/deployment/openmote-cc2538 \
6tisch/simple-node/openmote-cc2538 \
6tisch/simple-node/openmote-cc2538:MAKE_WITH_SECURITY=1,MAKE_WITH_ORCHESTRA=1 \
TOOLS=

View File

@ -40,17 +40,21 @@
# To invoke the building for a specific platform, run:
# $ PLATFORMS=zoul ./build.sh
#
CONTIKI_NG_TOP_DIR="../.."
EXAMPLES_DIR=$CONTIKI_NG_TOP_DIR/examples
if [[ "$PLATFORMS" == "" ]]
then
PLATFORMS=`ls ../../arch/platform`
PLATFORMS=`ls $CONTIKI_NG_TOP_DIR/arch/platform`
fi
if [[ "$MAKEFILES" == "" ]]
then
MAKEFILES=`find ../../examples/ -name Makefile`
MAKEFILES=`find $EXAMPLES_DIR -name Makefile`
fi
HELLO_WORLD=$EXAMPLES_DIR/hello-world
# Set the make goal the first argument of the script or to "all" if called w/o arguments
if [[ $# -gt 0 ]]
then
@ -97,22 +101,14 @@ do
continue
fi
if [[ "$platform" == "srf06-cc26xx" ]]
# Detect all boards for the current platform by calling
# make TARGET=$platform boards
# in the hello-world dir.
BOARDS=`make -s -C $HELLO_WORLD TARGET=$platform boards \
| grep -v "no boards" | rev | cut -f3- -d" " | rev`
if [[ -z $BOARDS ]]
then
# srf06-cc26xx has multiple boards
BOARDS="srf06/cc26xx srf06/cc13xx launchpad/cc2650 launchpad/cc1310 launchpad/cc1350 sensortag/cc2650 sensortag/cc1350"
elif [[ "$platform" == "simplelink" ]]
then
# SimpleLink has multiple boards
BOARDS="launchpad/cc1310 launchpad/cc1350 launchpad/cc1350-4 launchpad/cc2650 \
sensortag/cc1350 sensortag/cc2650 srf06/cc13x0 srf06/cc26x0 \
launchpad/cc1312r1 launchpad/cc1352r1 launchpad/cc1352p1 launchpad/cc1352p-2 launchpad/cc1352p-4 launchpad/cc26x2r1"
elif [[ "$platform" == "zoul" ]]
then
# Zoul has multiple boards
BOARDS="remote-reva remote-revb firefly-reva firefly orion"
else
# Other platforms have just a single board
BOARDS="default"
fi

View File

@ -1,62 +0,0 @@
Copyright (c) 2001-2003 Chris Liechti <cliechti@gmx.net>
All Rights Reserved.
This is the Python license. In short, you can use this product in
commercial and non-commercial applications, modify it, redistribute it.
A notification to the author when you use and/or modify it is welcome.
TERMS AND CONDITIONS FOR ACCESSING OR OTHERWISE USING THIS SOFTWARE
============================================
LICENSE AGREEMENT
-----------------
1. This LICENSE AGREEMENT is between the copyright holder of this
product, and the Individual or Organization ("Licensee") accessing
and otherwise using this product in source or binary form and its
associated documentation.
2. Subject to the terms and conditions of this License Agreement,
the copyright holder hereby grants Licensee a nonexclusive,
royalty-free, world-wide license to reproduce, analyze, test,
perform and/or display publicly, prepare derivative works, distribute,
and otherwise use this product alone or in any derivative version,
provided, however, that copyright holders License Agreement and
copyright holders notice of copyright are retained in this product
alone or in any derivative version prepared by Licensee.
3. In the event Licensee prepares a derivative work that is based on
or incorporates this product or any part thereof, and wants to make
the derivative work available to others as provided herein, then
Licensee hereby agrees to include in any such work a brief summary of
the changes made to this product.
4. The copyright holder is making this product available to Licensee
on an "AS IS" basis. THE COPYRIGHT HOLDER MAKES NO REPRESENTATIONS
OR WARRANTIES, EXPRESS OR IMPLIED. BY WAY OF EXAMPLE, BUT NOT
LIMITATION, THE COPYRIGHT HOLDER MAKES NO AND DISCLAIMS ANY
REPRESENTATION OR WARRANTY OF MERCHANTABILITY OR FITNESS FOR
ANY PARTICULAR PURPOSE OR THAT THE USE OF THIS PRODUCT WILL
NOT INFRINGE ANY THIRD PARTY RIGHTS.
5. THE COPYRIGHT HOLDER SHALL NOT BE LIABLE TO LICENSEE OR ANY
OTHER USERS OF THIS PRODUCT FOR ANY INCIDENTAL, SPECIAL, OR
CONSEQUENTIAL DAMAGES OR LOSS AS A RESULT OF MODIFYING,
DISTRIBUTING, OR OTHERWISE USING THIS PRODUCT, OR ANY
DERIVATIVE THEREOF, EVEN IF ADVISED OF THE POSSIBILITY
THEREOF.
6. This License Agreement will automatically terminate upon a
material breach of its terms and conditions.
7. Nothing in this License Agreement shall be deemed to create any
relationship of agency, partnership, or joint venture between the
copyright holder and Licensee. This License Agreement does not grant
permission to use trademarks or trade names from the copyright holder
in a trademark sense to endorse or promote products or services of
Licensee, or any third party.
8. By copying, installing or otherwise using this product, Licensee
agrees to be bound by the terms and conditions of this License
Agreement.

View File

@ -1,295 +0,0 @@
#!/usr/bin/perl -w
use strict;
# $Id: motelist-z1,v 1.1 2010/08/24 15:48:20 joxe Exp $
# @author Cory Sharp <cory@moteiv.com>
# @author Joe Polastre
my $help = <<'EOF';
usage: motelist [options]
$Revision: 1.1 $
options:
-h display this help
-c compact format, not pretty but easier for parsing
-f specify the usb-serial file (for smote.cs)
-k kernel version: 2.4, 2.6, auto (default)
-m method to scan usb: procfs, sysfs, auto (default)
-dev_prefix force the device prefix for the serial device
-usb display extra usb information
-b specify which Zolertia board to list (z1, remote, etc)
EOF
my %Opt = (
compact => 0,
usb => 0,
board => "",
method => "auto",
kernel => "auto",
dev_prefix => [ "/dev/usb/tts/", "/dev/ttyUSB", "/dev/tts/USB" ],
usbserial => "sudo cat /proc/tty/driver/usbserial |",
);
while (@ARGV) {
last unless $ARGV[0] =~ /^-/;
my $opt = shift @ARGV;
if( $opt eq "-h" ) { print "$help\n"; exit 0; }
elsif( $opt eq "-c" ) { $Opt{compact} = 1; }
elsif( $opt eq "-f" ) { $Opt{usbserial} = shift @ARGV; }
elsif( $opt eq "-k" ) { $Opt{kernel} = shift @ARGV; }
elsif( $opt eq "-m" ) { $Opt{method} = shift @ARGV; }
elsif( $opt eq "-dev_prefix" ) { $Opt{dev_prefix} = shift @ARGV; }
elsif( $opt eq "-usb" ) { $Opt{usb} = 1; }
elsif( $opt eq "-b" ) { $Opt{board} = shift @ARGV; }
else { print STDERR "$help\nerror, unknown command line option $opt\n"; exit 1; }
}
if( $Opt{kernel} eq "auto" ) {
$Opt{kernel} = "unknown";
$Opt{kernel} = $1 if snarf("/proc/version") =~ /\bLinux version (\d+\.\d+)/;
}
if( $Opt{method} eq "auto" ) {
$Opt{method} = ($Opt{kernel} eq "2.4") ? "procfs" : "sysfs";
}
if( $Opt{board} eq "z1" ) {
$Opt{board} = "Zolertia Z1";
} elsif( $Opt{board} eq "remote" ) {
$Opt{board} = "Zolertia RE-Mote platform";
} elsif( $Opt{board} eq "firefly" ) {
$Opt{board} = "Zolertia Firefly platform";
} elsif( $Opt{board} eq "orion" ) {
$Opt{board} = "Zolertia Orion Ethernet router";
}
my @devs = $Opt{method} eq "procfs" ? scan_procfs() : scan_sysfs();
print_motelist( sort { cmp_usbdev($a,$b) } @devs );
#
# SysFS
#
sub scan_sysfs {
my $tmp = '($_->{UsbVendor}||"") eq "10c4" && ($_->{UsbProduct}||"") eq "ea60"';
if($Opt{board}) {
$tmp = '($_->{ProductString}||"") eq $Opt{board} && ' . $tmp
}
# Scan /sys/bus/usb/drivers/usb for CP210x devices
my @cpdevs =
grep { eval "$tmp" }
map { {
SysPath => $_,
UsbVendor => snarf("$_/idVendor",1),
UsbProduct => snarf("$_/idProduct",1),
ProductString => snarf("$_/product",1),
} }
glob("/sys/bus/usb/drivers/usb/*");
# Gather information about each CP210x device
for my $f (@cpdevs) {
my $syspath = $f->{SysPath};
$f->{InfoSerial} = snarf("$syspath/serial",1);
$f->{InfoManufacturer} = snarf("$syspath/manufacturer",1);
$f->{InfoProduct} = snarf("$syspath/product",1);
$f->{UsbDevNum} = snarf("$syspath/devnum",1);
my $devstr = readlink($syspath);
if( $devstr =~ m{([^/]+)/usb(\d+)/.*-([^/]+)$} ) {
$f->{UsbPath} = "usb-$1-$3";
$f->{UsbBusNum} = $2;
}
($f->{SysDev} = $syspath) =~ s{^.*/}{};
my $port = "$syspath/$f->{SysDev}:1.0";
($f->{DriverName} = readlink("$port/driver")) =~ s{^.*/}{} if -l "$port/driver";
($f->{SerialDevName} = (glob("$port/tty*"),undef)[0]) =~ s{^.*/}{};
$f->{SerialDevNum} = $1 if $f->{SerialDevName} =~ /(\d+)/;
$f->{SerialDevName} = getSerialDevName( $f->{SerialDevNum} ) || " (none)";
}
return @cpdevs;
}
#
# Scan Procfs
#
sub scan_procfs {
my $text_devs = snarf("< /proc/bus/usb/devices");
my $text_serial = snarf($Opt{usbserial});
my @usbdevs = map { {parse_usb_devices_text($_)} }
grep { !/^\s*$/ } split /\n+(?=T:)/, $text_devs;
my %usbtree = build_usb_tree( @usbdevs );
my %usbserialtree = build_usbserial_tree( $text_serial );
for my $tts ( values %usbserialtree ) {
$usbtree{usbkey($tts->{path})}{usbserial} = $tts if defined $tts->{path};
}
my @cpdevs = map { {
UsbVendor => $_->{Vendor},
UsbProduct => $_->{ProdID},
InfoManufacturer => $_->{Manufacturer},
InfoProduct => $_->{Product},
InfoSerial => $_->{SerialNumber},
UsbBusNum => $_->{nbus},
UsbDevNum => $_->{ndev},
UsbPath => (($Opt{kernel} eq "2.4") ? $_->{usbserial}{path} : $_->{usbpath}),
DriverName => $_->{driver},
SerialDevNum => $_->{usbserial}{tts},
SerialDevName => getSerialDevName($_->{usbserial}{tts}) || " (none)",
} }
grep { ($_->{Vendor}||"") eq "0403" && ($_->{ProdID}||"") eq "6001" }
values %usbtree;
return @cpdevs;
}
sub build_usb_tree {
my @devs = @_;
my %tree = ();
for my $dev (sort { $a->{Lev} <=> $b->{Lev} } @devs) {
my ($bus,$lev,$prnt) = ( $dev->{Bus}+0, $dev->{Lev}+0, $dev->{Prnt}+0 );
my $devnum = $dev->{"Dev#"}+0;
$dev->{nbus} = $bus;
$dev->{ndev} = $devnum;
$tree{"bus$bus"} = {} unless exists $tree{"bus$bus"};
$tree{"bus$bus"}{"dev$devnum"} = $dev;
if( $lev == 0 ) {
$dev->{usbpath} = "usb-$dev->{SerialNumber}";
} else {
my $sep = ($lev==1) ? "-" : ".";
$dev->{parent} = $tree{"bus$bus"}{"dev$prnt"};
$dev->{usbpath} = $dev->{parent}{usbpath} . $sep . ($dev->{Port}+1);
}
$tree{usbkey($dev->{usbpath})} = $dev;
}
return %tree;
}
sub parse_usb_devices_text {
my $text = shift;
$text =~ s/^\S+\s*//gm;
return ($text =~ m/([^\s=]+)=\s*(.*?\S)\s*(?=[^\s=]+=|$)/mg);
}
sub build_usbserial_tree {
my $text = shift;
my %tree = ();
while( $text =~ /^([^:]+):(.*)/mg ) {
my ($tts,$params) = ($1,$2);
$tree{$tts} = { tts => $tts };
while ($params =~ m/\s+([^:]+):(?:"([^"]*)"|(\S+))/g) {
$tree{$tts}{$1} = $2||$3;
}
}
return %tree;
}
sub usbkey {
if( $Opt{kernel} eq "2.4" ) {
(my $key = $_[0]) =~ s/^.*-//;
return $key;
}
return $_[0];
}
#
# getSerialDevName
#
# For each device, force to use dev_prefix if it's not an array. Otherwise,
# assume it's a list of candidate prefixes. Check them and commit to the
# first one that actually exists.
#
sub getSerialDevName {
my $devnum = shift;
my $devname = undef;
if( defined $devnum ) {
if( ref($Opt{dev_prefix}) eq "ARRAY" ) {
$devname = $devnum;
for my $prefix (@{$Opt{dev_prefix}}) {
my $file = $prefix . $devnum;
if( -e $file ) { $devname = $file; last; }
}
} else {
$devname = $Opt{dev_prefix} . $devnum;
}
}
return $devname;
}
#
# Print motelist
#
sub print_motelist {
my @devs = @_;
# If none were found, quit
if( @devs == 0 ) {
print "No devices found.\n";
return;
}
# Print a header
if( !$Opt{compact} ) {
if( $Opt{usb} ) {
print << "EOF" unless $Opt{compact};
--- --- ------------------------ -------------- ---------------- -------------------------------------
Bus Dev USB Path Reference Device Description
--- --- ------------------------ -------------- ---------------- -------------------------------------
EOF
} else {
print << "EOF" unless $Opt{compact};
-------------- ---------------- ---------------------------------------------
Reference Device Description
-------------- ---------------- ---------------------------------------------
EOF
}
}
# Print the usb information
for my $dev (sort { cmp_usbdev($a,$b) } @devs) {
my $desc = join( " ", $dev->{InfoManufacturer}||"", $dev->{InfoProduct}||"" ) || " (none)";
my @output = ( $dev->{InfoSerial}||" (none)", $dev->{SerialDevName}, $desc );
@output = ( $dev->{UsbBusNum}, $dev->{UsbDevNum}, $dev->{UsbPath}, @output ) if $Opt{usb};
if( $Opt{compact} ) {
print join(",",@output) . "\n";
} else {
printf( ($Opt{usb}?"%3d %3d %-24s ":"")."%-14s %-16s %s\n", @output );
}
}
}
#
# Cmp Usbdev's
#
sub cmp_usbdev {
my ($a,$b) = @_;
if( defined $a->{SerialDevNum} ) {
if( defined $b->{SerialDevNum} ) {
return $a->{SerialDevNum} <=> $b->{SerialDevNum};
}
return -1;
}
return 1 if defined $b->{SerialDevNum};
return ($a->{InfoSerial}||"") cmp ($b->{InfoSerial}||"");
}
#
# Read a file in
#
sub snarf {
open my $fh, $_[0] or return undef;
my $text = do{local $/;<$fh>};
close $fh;
$text =~ s/\s+$// if $_[1];
return $text;
}

View File

@ -1,75 +0,0 @@
#!/usr/bin/perl -w
use strict;
my $help = <<'EOF';
usage: motelist [options]
options:
-h display this help
-c compact format, not pretty but easier for parsing
EOF
my %Opt = (
compact => 0,
dev_prefix => [ "/dev/tty.SLAB" ],
);
while (@ARGV) {
last unless $ARGV[0] =~ /^-/;
my $opt = shift @ARGV;
if( $opt eq "-h" ) { print "$help\n"; exit 0; }
elsif( $opt eq "-c" ) { $Opt{compact} = 1; }
else { print STDERR "$help\nerror, unknown command line option $opt\n"; exit 1; }
}
print_motelist( scan_dev() );
#
# Scan /dev for tty.SLAB*
#
sub scan_dev {
my @devs;
foreach (`ls /dev/tty.SLAB* 2>&1`) {
my($dev, $serial) = /(\/dev\/tty.SLAB(\S+))/;
if ($serial ne "*:") {
my $d;
$d->{"InfoSerial"} = $serial;
$d->{"SerialDevName"} = $dev;
push(@devs, $d);
}
}
return @devs;
}
#
# Print motelist
#
sub print_motelist {
my @devs = @_;
# If none were found, quit
if( @devs == 0 ) {
#print "No devices found.\n";
return;
}
# Print a header
if( !$Opt{compact} ) {
print << "EOF" unless $Opt{compact};
Reference Device Description
---------- --------------------------- ---------------------------------------
EOF
}
# Print the usb information
for my $dev (@devs) {
my $desc = "(none)";
my @output = ( $dev->{"InfoSerial"}, $dev->{"SerialDevName"}, $desc );
if( $Opt{compact} ) {
print join(",",@output) . "\n";
} else {
printf( "%-10s %-27s %s\n", @output );
}
}
}