Add CC26xx CPU files

This commit is contained in:
Jonas Olsson 2015-02-25 13:09:56 +01:00
parent 0c7d261465
commit 5e5e9b92fd
39 changed files with 10923 additions and 0 deletions

132
cpu/cc26xx/Makefile.cc26xx Normal file
View File

@ -0,0 +1,132 @@
CC = arm-none-eabi-gcc
CPP = arm-none-eabi-cpp
LD = arm-none-eabi-gcc
AR = arm-none-eabi-ar
OBJCOPY = arm-none-eabi-objcopy
OBJDUMP = arm-none-eabi-objdump
NM = arm-none-eabi-nm
SIZE = arm-none-eabi-size
### TI CC26xxware out-of-tree
### TI_CC26XXWARE is the home directory of the cc26xxware
### It MUST be provided as a path relative to $(CONTIKI)
### For example, if
### CONTIKI = /home/user/contiki
### and TI_CC26XXWARE is stored in
### /home/user/cc26xxware
### then set
### TI_CC26XXWARE = ../cc26xxware
ifndef TI_CC26XXWARE
$(error TI_CC26XXWARE not defined. Please see the README)
endif
### cc26xxware sources will be added to the MODULES list
TI_CC26XXWARE_SRC = $(TI_CC26XXWARE)/driverlib
### The directory with startup sources will be added to the CONTIKI_CPU_DIRS
### and the sources therein are added to the sources list explicitly. They are
### also listed explicitly in the linker command (through TARGET_STARTFILES),
### to make sure they always get linked in the image
TI_CC26XXWARE_STARTUP = ../../$(TI_CC26XXWARE)/startup_files
TI_CC26XXWARE_STARTUP_SRCS = ccfg.c startup_gcc.c
### MODULES will add some of these to the include pach, but we need to add
### them earlier to prevent filename clashes with Contiki core files
CFLAGS += -I$(CONTIKI)/$(TI_CC26XXWARE) -I$(CONTIKI)/$(TI_CC26XXWARE_SRC)
CFLAGS += -I$(CONTIKI)/$(TI_CC26XXWARE)/inc
MODULES += $(TI_CC26XXWARE_SRC)
LDSCRIPT = $(CONTIKI_CPU)/cc26xx.ld
CFLAGS += -mcpu=cortex-m3 -mthumb -mlittle-endian
CFLAGS += -ffunction-sections -fdata-sections
CFLAGS += -fshort-enums -fomit-frame-pointer -fno-strict-aliasing
CFLAGS += -Wall -std=c99
### Workaround for driverlib's cpu.h which tests if defined(gcc)
### Delete if it gets fixed or if we stop using the driverlib
CFLAGS += -Dgcc=__GNUC__
LDFLAGS += -mcpu=cortex-m3 -mthumb -mlittle-endian -nostartfiles
LDFLAGS += -T $(LDSCRIPT)
LDFLAGS += -Wl,--gc-sections,--sort-section=alignment
LDFLAGS += -Wl,-Map=$(@:.elf=-$(TARGET).map),--cref,--no-warn-mismatch
OBJCOPY_FLAGS += -O binary --gap-fill 0xff
OBJDUMP_FLAGS += --disassemble --source --disassembler-options=force-thumb
### Are we building with code size optimisations?
ifeq ($(SMALL),1)
CFLAGS += -Os
else
CFLAGS += -O2
endif
### If the user-specified a Node ID, pass a define
ifdef NODEID
CFLAGS += -DIEEE_ADDR_NODE_ID=$(NODEID)
endif
### CPU-dependent cleanup files
CLEAN += symbols.c symbols.h *.d *.elf *.hex
### CPU-dependent directories
CONTIKI_CPU_DIRS = . dev dev/rfc-api $(TI_CC26XXWARE_STARTUP)
### Use the existing debug I/O in cpu/arm/common
CONTIKI_CPU_DIRS += ../arm/common/dbg-io
### CPU-dependent source files
CONTIKI_CPU_SOURCEFILES += clock.c rtimer-arch.c cc26xx-rtc.c uart.c
CONTIKI_CPU_SOURCEFILES += cc26xx-rf.c contiki-watchdog.c
CONTIKI_CPU_SOURCEFILES += putchar.c ieee-addr.c batmon-sensor.c
CONTIKI_CPU_SOURCEFILES += slip-arch.c slip.c cc26xx-uart.c lpm.c
CONTIKI_CPU_SOURCEFILES += gpio-interrupt.c
DEBUG_IO_SOURCEFILES += dbg-printf.c dbg-snprintf.c dbg-sprintf.c strformat.c
CONTIKI_SOURCEFILES += $(CONTIKI_CPU_SOURCEFILES) $(DEBUG_IO_SOURCEFILES)
TARGET_START_SOURCEFILES += fault-handlers.c $(TI_CC26XXWARE_STARTUP_SRCS)
TARGET_STARTFILES = $(addprefix $(OBJECTDIR)/,$(call oname, $(TARGET_START_SOURCEFILES)))
### Don't treat the .elf as intermediate
.PRECIOUS: %.elf %.hex %.bin
### Always re-build ieee-addr.o in case the command line passes a new NODEID
FORCE:
$(OBJECTDIR)/ieee-addr.o: ieee-addr.c FORCE | $(OBJECTDIR)
$(TRACE_CC)
$(Q)$(CC) $(CFLAGS) -c $< -o $@
### Compilation rules
CUSTOM_RULE_LINK=1
%.elf: $(TARGET_STARTFILES) %.co $(PROJECT_OBJECTFILES) $(PROJECT_LIBRARIES) contiki-$(TARGET).a $(LDSCRIPT)
$(TRACE_LD)
$(Q)$(LD) $(LDFLAGS) ${filter-out $(LDSCRIPT) %.a,$^} ${filter %.a,$^} $(TARGET_LIBFILES) -lm -o $@
%.hex: %.elf
$(OBJCOPY) -O ihex $< $@
%.bin: %.elf
$(OBJCOPY) $(OBJCOPY_FLAGS) $< $@
%.lst: %.elf
$(OBJDUMP) $(OBJDUMP_FLAGS) $< > $@
### We don't really need the .hex and .bin for the .$(TARGET) but let's make
### sure they get built
%.$(TARGET): %.elf %.hex %.bin
cp $< $@
# a target that gives a user-friendly memory profile, taking into account the RAM
# that is statically occupied by the stack as defined in the linker script
# see $(LDSCRIPT)
RAM_SIZE = 0x00003E00
FLASH_SIZE = 0x0001E000
STACK_SIZE = 0
%.size: %.$(TARGET)
@$(SIZE) -A $< | egrep "data|bss" | awk '{s+=$$2} END {s=s+$(STACK_SIZE); f=$(RAM_SIZE)-s; printf "[RAM] used %6d, free %6d\n",s,f;}'
@$(SIZE) -A $< | egrep "text|isr_vector" | awk '{s+=$$2} END {f=$(FLASH_SIZE)-s; printf "[Flash] used %6d, free %6d\n",s,f;}'

74
cpu/cc26xx/cc26xx-model.h Normal file
View File

@ -0,0 +1,74 @@
/*
* Copyright (c) 2015, 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
* @{
*
* \defgroup cc26xx-models CC26xx models
*
* The CC26xx comes out in various flavours. Most notable within the context
* of this Contiki port: The CC2630 with IEEE (but no BLE) support and the
* CC2650 with IEEE and BLE support.
*
* This port supports both models and will automatically turn off the BLE code
* if the CC2630 is selected.
*
* @{
*/
/**
* \file
* Header file with definitions relating to various CC26xx variants
*/
/*---------------------------------------------------------------------------*/
#ifndef CC26XX_MODEL_H_
#define CC26XX_MODEL_H_
/*---------------------------------------------------------------------------*/
#include "contiki-conf.h"
/*---------------------------------------------------------------------------*/
#ifdef CC26XX_MODEL_CONF_CPU_VARIANT
#define CC26XX_MODEL_CPU_VARIANT CC26XX_MODEL_CONF_CPU_VARIANT
#else
#define CC26XX_MODEL_CPU_VARIANT 2650
#endif
#if (CC26XX_MODEL_CPU_VARIANT != 2630) && (CC26XX_MODEL_CPU_VARIANT != 2650)
#error Incorrect CC26xx variant selected.
#error Check the value of CC26XX_MODEL_CONF_CPU_VARIANT
#error Supported values: 2630 and 2650
#endif
/*---------------------------------------------------------------------------*/
#endif /* CC26XX_MODEL_H_ */
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
*/

103
cpu/cc26xx/cc26xx.ld Normal file
View File

@ -0,0 +1,103 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/* CC26XX linker script */
/* Entry Point */
ENTRY(ResetISR)
MEMORY
{
/* Flash Size 128 KB minus the CCA area below (76 bytes) */
FLASH (RX) : ORIGIN = 0x00000000, LENGTH = 0x0001FFAC
/*
* Customer Configuration Area and Bootloader Backdoor configuration
* in flash, up to 80 bytes
*/
FLASH_CCFG (RX) : ORIGIN = 0x0001FFAC, LENGTH = 84
/* RAM Size 20KB (PG2.1) */
SRAM (RWX) : ORIGIN = 0x20000000, LENGTH = 0x00005000
}
/*. Highest address of the stack. Used in startup file .*/
_estack = ORIGIN(SRAM) + LENGTH(SRAM); /* End of SRAM */
/*. Generate a link error if heap and stack dont fit into RAM .*/
_Min_Heap_Size = 0;
_Min_Stack_Size = 0x100;
SECTIONS
{
.text :
{
_text = .;
KEEP(*(.vectors))
*(.text*)
*(.rodata*)
_etext = .;
} > FLASH = 0
.data :
{
_data = .;
*(vtable)
*(.data*)
_edata = .;
} > SRAM AT > FLASH
.ARM.exidx :
{
*(.ARM.exidx*)
} > FLASH
.bss :
{
_bss = .;
*(.bss*)
*(COMMON)
_ebss = .;
} > SRAM
.ccfg :
{
KEEP(*(.ccfg))
} > FLASH_CCFG
/* User_heap_stack section, used to check that there is enough RAM left */
._user_heap_stack :
{
. = ALIGN(4);
. = . + _Min_Heap_Size;
. = . + _Min_Stack_Size;
. = ALIGN(4);
} >SRAM
}

189
cpu/cc26xx/clock.c Normal file
View File

@ -0,0 +1,189 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup platform
* @{
*
* \defgroup cc26xx-platforms TI CC26xx-powered Platforms
* @{
*
* \defgroup cc26xx The TI CC26xx CPU
* @{
*
* \addtogroup cc26xx-clocks
* @{
*
* \defgroup cc26xx-software-clock CC26xx Software Clock
*
* Implementation of the clock module for the cc26xx.
*
* The software clock uses the facilities provided by the AON RTC driver
* @{
*
* \file
* Software clock implementation for the TI CC26xx
*/
/*---------------------------------------------------------------------------*/
#include "contiki.h"
#include "ti-lib.h"
/*---------------------------------------------------------------------------*/
static volatile clock_time_t count;
static volatile clock_time_t second_countdown;
static volatile unsigned long secs;
/*---------------------------------------------------------------------------*/
static void
power_domain_on(void)
{
ti_lib_prcm_power_domain_on(PRCM_DOMAIN_PERIPH);
while(ti_lib_prcm_power_domain_status(PRCM_DOMAIN_PERIPH) !=
PRCM_DOMAIN_POWER_ON);
}
/*---------------------------------------------------------------------------*/
void
clock_init(void)
{
count = 0;
secs = 0;
second_countdown = CLOCK_SECOND;
/*
* Here, we configure GPT0 Timer A, which we subsequently use in
* clock_delay_usec
*
* First, enable GPT0 in run mode. We don't need it in sleep mode
*/
ti_lib_prcm_peripheral_run_enable(PRCM_PERIPH_TIMER0);
ti_lib_prcm_load_set();
while(!ti_lib_prcm_load_get());
/* Disable both GPT0 timers */
HWREG(GPT0_BASE + GPT_O_CTL) &= ~(GPT_CTL_TAEN | GPT_CTL_TBEN);
/*
* We assume that the clock is running at 48MHz, we use GPT0 Timer A,
* one-shot, countdown, prescaled by 48 gives us 1 tick per usec
*/
ti_lib_timer_configure(GPT0_BASE,
TIMER_CFG_SPLIT_PAIR | TIMER_CFG_B_ONE_SHOT);
/* Global config: split pair (2 x 16-bit wide) */
HWREG(GPT0_BASE + GPT_O_CFG) = TIMER_CFG_SPLIT_PAIR >> 24;
/*
* Pre-scale value 47 pre-scales by 48
*
* ToDo: The theoretical value here should be 47 (to provide x48 prescale)
* However, 49 seems to give results much closer to the desired delay
*/
ti_lib_timer_prescale_set(GPT0_BASE, TIMER_B, 49);
/* GPT0 / Timer B: One shot, PWM interrupt enable */
HWREG(GPT0_BASE + GPT_O_TBMR) =
((TIMER_CFG_B_ONE_SHOT >> 8) & 0xFF) | GPT_TBMR_TBPWMIE;
}
/*---------------------------------------------------------------------------*/
CCIF clock_time_t
clock_time(void)
{
return count;
}
/*---------------------------------------------------------------------------*/
void
clock_update(void)
{
count++;
if(etimer_pending()) {
etimer_request_poll();
}
if(--second_countdown == 0) {
secs++;
second_countdown = CLOCK_SECOND;
}
}
/*---------------------------------------------------------------------------*/
void
clock_set_seconds(unsigned long sec)
{
secs = sec;
}
/*---------------------------------------------------------------------------*/
CCIF unsigned long
clock_seconds(void)
{
return secs;
}
/*---------------------------------------------------------------------------*/
void
clock_wait(clock_time_t i)
{
clock_time_t start;
start = clock_time();
while(clock_time() - start < (clock_time_t)i);
}
/*---------------------------------------------------------------------------*/
void
clock_delay_usec(uint16_t len)
{
if(ti_lib_prcm_power_domain_status(PRCM_DOMAIN_PERIPH) !=
PRCM_DOMAIN_POWER_ON) {
power_domain_on();
}
ti_lib_timer_load_set(GPT0_BASE, TIMER_B, len);
ti_lib_timer_enable(GPT0_BASE, TIMER_B);
/*
* Wait for TBEN to clear. CC26xxware does not provide us with a convenient
* function, hence the direct register access here
*/
while(HWREG(GPT0_BASE | GPT_O_CTL) & GPT_CTL_TBEN);
}
/*---------------------------------------------------------------------------*/
/**
* \brief Obsolete delay function but we implement it here since some code
* still uses it
*/
void
clock_delay(unsigned int i)
{
clock_delay_usec(i);
}
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
* @}
* @}
* @}
*/

65
cpu/cc26xx/dbg.h Normal file
View File

@ -0,0 +1,65 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup cc26xx
* @{
*
* \defgroup cc26xx-char-io CC26xx Character I/O
*
* CC26xx CPU-specific functions for debugging and SLIP I/O
* @{
*
* \file
* Header file for the CC26xx Debug I/O module
*/
#ifndef DBG_H_
#define DBG_H_
/*---------------------------------------------------------------------------*/
#include "contiki-conf.h"
/*---------------------------------------------------------------------------*/
/**
* \brief Print a stream of bytes
* \param seq A pointer to the stream
* \param len The number of bytes to print
* \return The number of printed bytes
*
* This function is an arch-specific implementation required by the dbg-io
* API in cpu/arm/common/dbg-io. It prints a stream of bytes over the
* peripheral used by the platform.
*/
unsigned int dbg_send_bytes(const unsigned char *seq, unsigned int len);
/*---------------------------------------------------------------------------*/
#endif /* DBG_H_ */
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
*/

49
cpu/cc26xx/debug-uart.h Normal file
View File

@ -0,0 +1,49 @@
/*
* Copyright (c) 2012, 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-char-io
* @{
*
* \file
* This file is here because DBG I/O expects it to be. It just includes
* our own dbg.h which has a non-misleading name and which also adheres
* to Contiki's naming convention
*/
/*---------------------------------------------------------------------------*/
#ifndef DEBUG_UART_H_
#define DEBUG_UART_H_
/*---------------------------------------------------------------------------*/
#include "dbg.h"
/*---------------------------------------------------------------------------*/
#endif /* DEBUG_UART_H_ */
/*---------------------------------------------------------------------------*/
/** @} */

View File

@ -0,0 +1,143 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup cc26xx-batmon
* @{
*
* \file
* Driver for the CC26xx AON battery monitor
*/
/*---------------------------------------------------------------------------*/
#include "contiki-conf.h"
#include "lib/sensors.h"
#include "batmon-sensor.h"
#include "ti-lib.h"
#include <stdint.h>
#include <stdio.h>
/*---------------------------------------------------------------------------*/
#define DEBUG 0
#if DEBUG
#define PRINTF(...) printf(__VA_ARGS__)
#else
#define PRINTF(...)
#endif
/*---------------------------------------------------------------------------*/
#define SENSOR_STATUS_DISABLED 0
#define SENSOR_STATUS_ENABLED 1
static int enabled = SENSOR_STATUS_DISABLED;
/*---------------------------------------------------------------------------*/
/**
* \brief Returns a reading from the sensor
* \param type BATMON_SENSOR_TYPE_TEMP or BATMON_SENSOR_TYPE_VOLT
*
* \return The raw sensor reading, not converted to human-readable form
*/
static int
value(int type)
{
uint32_t tmp_value;
if(enabled == SENSOR_STATUS_DISABLED) {
PRINTF("Sensor Disabled\n");
return 0;
}
if(type == BATMON_SENSOR_TYPE_TEMP) {
tmp_value = ti_lib_aon_batmon_temperature_get();
} else if(type == BATMON_SENSOR_TYPE_VOLT) {
tmp_value = ti_lib_aon_batmon_battery_voltage_get();
} else {
PRINTF("Invalid type\n");
return 0;
}
return (int)tmp_value;
}
/*---------------------------------------------------------------------------*/
/**
* \brief Configuration function for the battery monitor sensor.
*
* \param type Activate, enable or disable the sensor. See below
* \param enable If
*
* When type == SENSORS_HW_INIT we turn on the hardware
* When type == SENSORS_ACTIVE and enable==1 we enable the sensor
* When type == SENSORS_ACTIVE and enable==0 we disable the sensor
*/
static int
configure(int type, int enable)
{
switch(type) {
case SENSORS_HW_INIT:
ti_lib_aon_batmon_enable();
ti_lib_aon_batmon_measurement_cycle_set(AON_BATMON_CYCLE_32);
enabled = SENSOR_STATUS_ENABLED;
break;
case SENSORS_ACTIVE:
if(enable) {
ti_lib_aon_batmon_enable();
enabled = SENSOR_STATUS_ENABLED;
} else {
ti_lib_aon_batmon_disable();
enabled = SENSOR_STATUS_DISABLED;
}
break;
default:
break;
}
return enabled;
}
/*---------------------------------------------------------------------------*/
/**
* \brief Returns the status of the sensor
* \param type SENSORS_ACTIVE or SENSORS_READY
* \return 1 if the sensor is enabled
*/
static int
status(int type)
{
switch(type) {
case SENSORS_ACTIVE:
case SENSORS_READY:
return enabled;
break;
default:
break;
}
return SENSOR_STATUS_DISABLED;
}
/*---------------------------------------------------------------------------*/
SENSORS_SENSOR(batmon_sensor, "Battery Monitor", value, configure, status);
/*---------------------------------------------------------------------------*/
/** @} */

View File

@ -0,0 +1,57 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup cc26xx
* @{
*
* \defgroup cc26xx-batmon CC26xx BatMon sensor driver
*
* Driver for the on-chip battery voltage and chip temperature sensor.
* @{
*
* \file
* Header file for the CC26xx battery monitor
*/
/*---------------------------------------------------------------------------*/
#ifndef BATMON_SENSOR_H_
#define BATMON_SENSOR_H_
/*---------------------------------------------------------------------------*/
#define BATMON_SENSOR_TYPE_TEMP 1
#define BATMON_SENSOR_TYPE_VOLT 2
/*---------------------------------------------------------------------------*/
extern const struct sensors_sensor batmon_sensor;
/*---------------------------------------------------------------------------*/
#endif /* BATMON_SENSOR_H_ */
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
*/

2179
cpu/cc26xx/dev/cc26xx-rf.c Normal file

File diff suppressed because it is too large Load Diff

116
cpu/cc26xx/dev/cc26xx-rf.h Normal file
View File

@ -0,0 +1,116 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/**
* \addtogroup cc26xx
* @{
*
* \defgroup cc26xx-rf CC26xx RF driver
*
* The CC26xx RF has dual capability: It can operate in IEEE 802.15.4 mode at
* 2.4GHz, but it can also operate in BLE mode. This driver provides a fully
* contiki-compliant .15.4 functionality, but it also provides some very basic
* BLE capability.
*
* @{
*/
/**
* \file
* Header file for the CC26xx RF driver
*/
#ifndef CC26XX_RF_H_
#define CC26XX_RF_H_
/*---------------------------------------------------------------------------*/
#include "contiki.h"
#include "cc26xx-model.h"
#include "dev/radio.h"
/*---------------------------------------------------------------------------*/
#include <stdint.h>
/*---------------------------------------------------------------------------*/
#ifdef CC26XX_RF_CONF_CHANNEL
#define CC26XX_RF_CHANNEL CC26XX_RF_CONF_CHANNEL
#else
#define CC26XX_RF_CHANNEL 18
#endif /* CC26XX_RF_CONF_CHANNEL */
#ifdef CC26XX_RF_CONF_AUTOACK
#define CC26XX_RF_AUTOACK CC26XX_RF_CONF_AUTOACK
#else
#define CC26XX_RF_AUTOACK 1
#endif /* CC26XX_RF_CONF_AUTOACK */
#if defined (CC26XX_RF_CONF_BLE_SUPPORT) && (CC26XX_MODEL_CPU_VARIANT == 2650)
#define CC26XX_RF_BLE_SUPPORT CC26XX_RF_CONF_BLE_SUPPORT
#else
#define CC26XX_RF_BLE_SUPPORT 0
#endif
/*---------------------------------------------------------------------------
* RF Config
*---------------------------------------------------------------------------*/
/* Constants */
#define CC26XX_RF_CHANNEL_MIN 11
#define CC26XX_RF_CHANNEL_MAX 26
#define CC26XX_RF_CHANNEL_SPACING 5
#define CC26XX_RF_CHANNEL_SET_ERROR -1
#define CC26XX_RF_MAX_PACKET_LEN 127
#define CC26XX_RF_MIN_PACKET_LEN 4
/*---------------------------------------------------------------------------*/
/**
* \brief Set the device name to use with the BLE advertisement/beacon daemon
* \param interval The interval (ticks) between two consecutive beacon bursts
* \param name The device name to advertise
*
* If name is NULL it will be ignored. If interval==0 it will be ignored. Thus,
* this function can be used to configure a single parameter at a time if so
* desired.
*/
void cc26xx_rf_ble_beacond_config(clock_time_t interval, const char *name);
/**
* \brief Start the BLE advertisement/beacon daemon
* \return 1: Success, 0: Failure
*
* Before calling this function, the name to advertise must first be set by
* calling cc26xx_rf_ble_beacond_set_adv_name(). Otherwise, this function will
* return an error.
*/
uint8_t cc26xx_rf_ble_beacond_start(void);
/**
* \brief Stop the BLE advertisement/beacon daemon
*/
void cc26xx_rf_ble_beacond_stop(void);
/*---------------------------------------------------------------------------*/
#endif /* CC26XX_RF_H_ */
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
*/

127
cpu/cc26xx/dev/cc26xx-rtc.c Normal file
View File

@ -0,0 +1,127 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/**
* \addtogroup cc26xx-rtc
* @{
*
*/
/**
* \file
* Implementation of the CC26xx AON RTC driver
*/
#include "contiki.h"
#include "sys/energest.h"
#include "rtimer.h"
#include "lpm.h"
#include "ti-lib.h"
#include <stdint.h>
/*---------------------------------------------------------------------------*/
#define cc26xx_rtc_isr(...) AONRTCIntHandler(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* Prototype of a function in clock.c. Called every time the handler fires */
void clock_update(void);
/*---------------------------------------------------------------------------*/
void
cc26xx_rtc_init(void)
{
uint32_t compare_value;
/* Disable and clear interrupts */
ti_lib_int_master_disable();
ti_lib_aon_rtc_disable();
ti_lib_aon_rtc_event_clear(AON_RTC_CH0);
ti_lib_aon_rtc_event_clear(AON_RTC_CH2);
/* Setup the wakeup event */
ti_lib_aon_event_mcu_wake_up_set(AON_EVENT_MCU_WU0, AON_EVENT_RTC0);
ti_lib_aon_event_mcu_wake_up_set(AON_EVENT_MCU_WU1, AON_EVENT_RTC2);
/* Configure channel 2 in continuous compare, 128 ticks / sec */
compare_value = (RTIMER_SECOND / CLOCK_SECOND) +
ti_lib_aon_rtc_current_compare_value_get();
ti_lib_aon_rtc_compare_value_set(AON_RTC_CH2, compare_value);
ti_lib_aon_rtc_inc_value_ch2_set(RTIMER_SECOND / CLOCK_SECOND);
ti_lib_aon_rtc_mode_ch2_set(AON_RTC_MODE_CH2_CONTINUOUS);
/* Enable event generation for channels 0 and 2 and enable the RTC */
ti_lib_aon_rtc_combined_event_config(AON_RTC_CH0 | AON_RTC_CH2);
ti_lib_aon_rtc_channel_enable(AON_RTC_CH2);
ti_lib_aon_rtc_enable();
ti_lib_int_enable(INT_AON_RTC);
ti_lib_int_master_enable();
}
/*---------------------------------------------------------------------------*/
rtimer_clock_t
cc26xx_rtc_get_next_trigger()
{
rtimer_clock_t ch2 = ti_lib_aon_rtc_compare_value_get(AON_RTC_CH2);
if(HWREG(AON_RTC_BASE + AON_RTC_O_CHCTL) & AON_RTC_CHCTL_CH0_EN) {
rtimer_clock_t ch0 = ti_lib_aon_rtc_compare_value_get(AON_RTC_CH2);
return RTIMER_CLOCK_LT(ch0 ,ch2) ? ch0 : ch2;
}
return ch2;
}
/*---------------------------------------------------------------------------*/
void
cc26xx_rtc_schedule_one_shot(uint32_t ticks)
{
/* Set the channel to fire a one-shot compare event at time==ticks */
ti_lib_aon_rtc_compare_value_set(AON_RTC_CH0, ticks);
ti_lib_aon_rtc_channel_enable(AON_RTC_CH0);
}
/*---------------------------------------------------------------------------*/
/* The AON RTC interrupt handler */
void
cc26xx_rtc_isr(void)
{
ENERGEST_ON(ENERGEST_TYPE_IRQ);
if(ti_lib_aon_rtc_event_get(AON_RTC_CH0)) {
ti_lib_aon_rtc_event_clear(AON_RTC_CH0);
rtimer_run_next();
}
if(ti_lib_aon_rtc_event_get(AON_RTC_CH2)) {
ti_lib_aon_rtc_event_clear(AON_RTC_CH2);
clock_update();
}
ENERGEST_OFF(ENERGEST_TYPE_IRQ);
}
/*---------------------------------------------------------------------------*/
/** @} */

100
cpu/cc26xx/dev/cc26xx-rtc.h Normal file
View File

@ -0,0 +1,100 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/**
* \addtogroup cc26xx
* @{
*
* \defgroup cc26xx-clocks CC26xx clock and timer subsystem
*
* For the CC26xx cpu we use the AON RTC as the basis for all clocks and timers
*
* We configure the AON RTC's channel 2 to run in continuous mode, generating
* 128 interrupts / second. In continuous mode, the next compare event is
* scheduled by the hardware automatically; the events are equidistant and
* this also means we don't need the overhead of re-scheduling within the
* interrupt handler
*
* For rtimers, we use the RTC's channel 0 in one-shot compare mode. When the
* compare event fires, we call rtimer_run_next
*
* The RTC runs in all power modes except 'shutdown'
*
* \sa cpu/cc26xx/clock.c cpu/cc26xx/rtimer-arch.c
* @{
*
* \defgroup cc26xx-rtc CC26xx AON RTC driver
*
* Underpins the platform's software clocks and timers
*
* @{
* \file
* Header file for the CC26XX AON RTC driver
*/
#ifndef CC26XX_RTC_H_
#define CC26XX_RTC_H_
/*---------------------------------------------------------------------------*/
#include "contiki.h"
#include "rtimer.h"
#include <stdint.h>
/*---------------------------------------------------------------------------*/
/**
* \brief Initialise the CC26XX AON RTC module
*
* This timer configures the AON RTC's channel 2 to run in continuous mode
* This function must be called before clock_init() and rtimer_init()
*/
void cc26xx_rtc_init(void);
/**
* \brief Return the time of the next scheduled rtimer event
* \return The time at which the next rtimer event is due to fire
*
* This function will check both AON RTC channels and will only take CH0's
* compare into account if the channel is actually enabled
*/
rtimer_clock_t cc26xx_rtc_get_next_trigger(void);
/**
* \brief Schedule an AON RTC channel 0 one-shot compare event
* \param t The time when the event will be fired. This is an absolute
* time, in other words the event will fire AT time \e t,
* not IN \e t ticks
*/
void cc26xx_rtc_schedule_one_shot(uint32_t t);
/*---------------------------------------------------------------------------*/
#endif /* CC26XX_RTC_H_ */
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
* @}
*/

View File

@ -0,0 +1,249 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "contiki-conf.h"
#include "cc26xx-uart.h"
#include "hw_types.h"
#include "hw_memmap.h"
#include "sys_ctrl.h"
#include "prcm.h"
#include "ioc.h"
#include "uart.h"
#include "lpm.h"
#include "ti-lib.h"
#include "sys/energest.h"
#include <stdint.h>
/*---------------------------------------------------------------------------*/
/* Which events to trigger a UART interrupt */
#define CC26XX_UART_RX_INTERRUPT_TRIGGERS (UART_INT_RX | UART_INT_RT)
/* All interrupt masks */
#define CC26XX_UART_INTERRUPT_ALL (UART_INT_OE | UART_INT_BE | UART_INT_PE | \
UART_INT_FE | UART_INT_RT | UART_INT_TX | \
UART_INT_RX | UART_INT_CTS)
/*---------------------------------------------------------------------------*/
#define cc26xx_uart_isr UART0IntHandler
/*---------------------------------------------------------------------------*/
static int (*input_handler)(unsigned char c);
/*---------------------------------------------------------------------------*/
static void
power_domain_on(void)
{
ti_lib_prcm_power_domain_on(PRCM_DOMAIN_SERIAL);
while(ti_lib_prcm_power_domain_status(PRCM_DOMAIN_SERIAL)
!= PRCM_DOMAIN_POWER_ON);
}
/*---------------------------------------------------------------------------*/
static void
configure_baud_rate(void)
{
/*
* Configure the UART for 115,200, 8-N-1 operation.
* This function uses SysCtrlClockGet() to get the system clock
* frequency. This could be also be a variable or hard coded value
* instead of a function call.
*/
ti_lib_uart_config_set_exp_clk(UART0_BASE,
ti_lib_sys_ctrl_peripheral_clock_get(
PRCM_PERIPH_UART0,
SYSCTRL_SYSBUS_ON),
CC26XX_UART_CONF_BAUD_RATE,
(UART_CONFIG_WLEN_8 | UART_CONFIG_STOP_ONE |
UART_CONFIG_PAR_NONE));
}
/*---------------------------------------------------------------------------*/
static void
configure_registers(void)
{
/*
* Map UART signals to the correct GPIO pins and configure them as
* hardware controlled.
*/
ti_lib_ioc_pin_type_uart(UART0_BASE, BOARD_IOID_UART_RX, BOARD_IOID_UART_TX,
BOARD_IOID_UART_CTS, BOARD_IOID_UART_RTS);
configure_baud_rate();
/*
* Generate an RX interrupt at FIFO 1/2 full.
* We don't really care about the TX interrupt
*/
ti_lib_uart_fifo_level_set(UART0_BASE, UART_FIFO_TX7_8, UART_FIFO_RX4_8);
/* Configure which interrupts to generate: FIFO level or after RX timeout */
ti_lib_uart_int_enable(UART0_BASE, CC26XX_UART_RX_INTERRUPT_TRIGGERS);
}
/*---------------------------------------------------------------------------*/
static void
uart_on(void)
{
power_domain_on();
/* Configure baud rate and enable */
if((HWREG(UART0_BASE + UART_O_CTL) & UART_CTL_UARTEN) == 0) {
configure_registers();
/* Enable UART */
ti_lib_uart_enable(UART0_BASE);
}
}
/*---------------------------------------------------------------------------*/
static uint8_t
lpm_permit_max_pm_handler(void)
{
return LPM_MODE_MAX_SUPPORTED;
}
/*---------------------------------------------------------------------------*/
static void
lpm_drop_handler(uint8_t mode)
{
/* Do nothing if the PD is off */
if(ti_lib_prcm_power_domain_status(PRCM_DOMAIN_SERIAL)
!= PRCM_DOMAIN_POWER_ON) {
return;
}
/* Wait for outstanding TX to complete */
while(ti_lib_uart_busy(UART0_BASE));
/*
* Check our clock gate under Deep Sleep. If it's off, we can shut down. If
* it's on, this means that some other code module wants UART functionality
* during deep sleep, so we stay enabled
*/
if((HWREG(PRCM_BASE + PRCM_O_UARTCLKGDS) & 1) == 0) {
ti_lib_ioc_pin_type_gpio_input(BOARD_IOID_UART_RX);
ti_lib_ioc_pin_type_gpio_input(BOARD_IOID_UART_TX);
ti_lib_uart_disable(UART0_BASE);
}
}
/*---------------------------------------------------------------------------*/
static void
lpm_wakeup_handler(void)
{
uart_on();
}
/*---------------------------------------------------------------------------*/
/* Declare a data structure to register with LPM. */
LPM_MODULE(uart_module, lpm_permit_max_pm_handler,
lpm_drop_handler, lpm_wakeup_handler);
/*---------------------------------------------------------------------------*/
void
cc26xx_uart_init()
{
/* Exit without initialising if ports are misconfigured */
if(BOARD_IOID_UART_RX == IOID_UNUSED ||
BOARD_IOID_UART_TX == IOID_UNUSED) {
return;
}
/* Enable the serial domain and wait for domain to be on */
power_domain_on();
/* Enable the UART clock when running and sleeping */
ti_lib_prcm_peripheral_run_enable(PRCM_PERIPH_UART0);
/* Apply clock settings and wait for them to take effect */
ti_lib_prcm_load_set();
while(!ti_lib_prcm_load_get());
/* Disable Interrupts */
ti_lib_int_master_disable();
/* Make sure the peripheral is disabled */
ti_lib_uart_disable(UART0_BASE);
/* Disable all UART module interrupts */
ti_lib_uart_int_disable(UART0_BASE, CC26XX_UART_INTERRUPT_ALL);
configure_registers();
/* Acknowledge UART interrupts */
ti_lib_int_enable(INT_UART0);
/* Re-enable processor interrupts */
ti_lib_int_master_enable();
/* Enable UART */
ti_lib_uart_enable(UART0_BASE);
/* Register ourselves with the LPM module */
lpm_register_module(&uart_module);
}
/*---------------------------------------------------------------------------*/
void
cc26xx_uart_write_byte(uint8_t c)
{
if(ti_lib_prcm_power_domain_status(PRCM_DOMAIN_SERIAL)
!= PRCM_DOMAIN_POWER_ON) {
return;
}
ti_lib_uart_char_put(UART0_BASE, c);
}
/*---------------------------------------------------------------------------*/
void
cc26xx_uart_set_input(int (*input)(unsigned char c))
{
input_handler = input;
return;
}
/*---------------------------------------------------------------------------*/
void
cc26xx_uart_isr(void)
{
char the_char;
uint32_t flags;
ENERGEST_ON(ENERGEST_TYPE_IRQ);
/* Read out the masked interrupt status */
flags = ti_lib_uart_int_status(UART0_BASE, true);
/* Clear all UART interrupt flags */
ti_lib_uart_int_clear(UART0_BASE, CC26XX_UART_INTERRUPT_ALL);
if((flags & CC26XX_UART_RX_INTERRUPT_TRIGGERS) != 0) {
/*
* If this was a FIFO RX or an RX timeout, read all bytes available in the
* RX FIFO.
*/
while(ti_lib_uart_chars_avail(UART0_BASE)) {
the_char = ti_lib_uart_char_get_non_blocking(UART0_BASE);
if(input_handler != NULL) {
input_handler((unsigned char)the_char);
}
}
}
ENERGEST_OFF(ENERGEST_TYPE_IRQ);
}

View File

@ -0,0 +1,76 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/**
* \addtogroup cc26xx
* @{
*
* \defgroup cc26xx-uart CC26xx UARTs
*
* Driver for the CC26xx UART controller
* @{
*
* \file
* Header file for the CC26xx UART driver
*/
#ifndef CC26XX_UART_H_
#define CC26XX_UART_H_
#include <stdint.h>
/*---------------------------------------------------------------------------*/
/** \name UART functions
* @{
*/
/**
* \brief Initialises the UART controller, configures I/O control
* and interrupts
*/
void cc26xx_uart_init();
/**
* \brief Sends a single character down the UART
* \param b The character to transmit
*/
void cc26xx_uart_write_byte(uint8_t b);
/**
* \brief Assigns a callback to be called when the UART receives a byte
* \param input A pointer to the function
*/
void cc26xx_uart_set_input(int (*input)(unsigned char c));
/** @} */
/*---------------------------------------------------------------------------*/
#endif /* CC26XX_UART_H_ */
/**
* @}
* @}
*/

View File

@ -0,0 +1,99 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/**
* \addtogroup cc26xx-clocks
* @{
*
* \defgroup cc26xx-wdt CC26xx watchdog timer driver
*
* Driver for the CC26xx Watchdog Timer
*
* This file is not called watchdog.c because the filename is in use by
* TI CC26xxware
* @{
*
* \file
* Implementation of the cc26xx watchdog driver.
*/
#include "watchdog.h"
#include "ti-lib.h"
/*---------------------------------------------------------------------------*/
/**
* \brief Initialises the CC26xx WDT
*
* Simply sets the reload counter to a default value. The WDT is not started
* yet. To start it, watchdog_start() must be called.
*/
void
watchdog_init(void)
{
ti_lib_wathdog_reload_set(0xFFFFF);
}
/*---------------------------------------------------------------------------*/
/**
* \brief Starts the CC26xx WDT
*/
void
watchdog_start(void)
{
ti_lib_wathdog_reset_enable();
}
/*---------------------------------------------------------------------------*/
/**
* \brief Refreshes the CC26xx WDT
*/
void
watchdog_periodic(void)
{
ti_lib_wathdog_int_clear();
}
/*---------------------------------------------------------------------------*/
/**
* \brief Stub function to satisfy API requirements
*/
void
watchdog_stop(void)
{
}
/*---------------------------------------------------------------------------*/
/**
* \brief Manually trigger a WDT reboot
*/
void
watchdog_reboot(void)
{
watchdog_start();
while(1);
}
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
*/

View File

@ -0,0 +1,97 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
#include "ioc.h"
#include "gpio-interrupt.h"
#include "sys/energest.h"
#include "lpm.h"
#include "ti-lib.h"
#include <string.h>
/*---------------------------------------------------------------------------*/
#define gpio_interrupt_isr GPIOIntHandler
/*---------------------------------------------------------------------------*/
/* Handler array */
static gpio_interrupt_handler_t handlers[NUM_IO_MAX];
/*---------------------------------------------------------------------------*/
void
gpio_interrupt_register_handler(uint8_t ioid, gpio_interrupt_handler_t f)
{
uint8_t interrupts_disabled = ti_lib_int_master_disable();
/* Clear interrupts on specified pins */
ti_lib_gpio_event_clear(1 << ioid);
handlers[ioid] = f;
/* Re-enable interrupts */
if(!interrupts_disabled) {
ti_lib_int_master_enable();
}
}
/*---------------------------------------------------------------------------*/
void
gpio_interrupt_init()
{
int i;
for(i = 0; i < NUM_IO_MAX; i++) {
handlers[i] = NULL;
}
ti_lib_int_enable(INT_EDGE_DETECT);
}
/*---------------------------------------------------------------------------*/
void
gpio_interrupt_isr(void)
{
uint32_t pin_mask;
uint8_t i;
ENERGEST_ON(ENERGEST_TYPE_IRQ);
/* Read interrupt flags */
pin_mask = (HWREG(GPIO_BASE + GPIO_O_EVFLAGS31_0) & GPIO_PIN_MASK);
/* Clear the interrupt flags */
HWREG(GPIO_BASE + GPIO_O_EVFLAGS31_0) = pin_mask;
/* Run custom ISRs */
for(i = 0; i < NUM_GPIO_PINS; i++) {
/* Call the handler if there is one registered for this event */
if((pin_mask & (1 << i)) && handlers[i] != NULL) {
handlers[i](i);
}
}
ENERGEST_OFF(ENERGEST_TYPE_IRQ);
}
/*---------------------------------------------------------------------------*/

View File

@ -0,0 +1,71 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup cc26xx
* @{
*
* \defgroup cc26xx-gpio-interrupts CC26xx GPIO interrupt handling
*
* The CC26xx GPIO interrupt handler and an API which can be used by other
* parts of the code when they wish to be notified of a GPIO interrupt
*
* @{
*
* \file
* Header file for the CC26xx GPIO interrupt management
*/
/*---------------------------------------------------------------------------*/
#ifndef GPIO_INTERRUPT_H_
#define GPIO_INTERRUPT_H_
/*---------------------------------------------------------------------------*/
#include <stdint.h>
/*---------------------------------------------------------------------------*/
typedef void (*gpio_interrupt_handler_t)(uint8_t ioid);
/*---------------------------------------------------------------------------*/
/** \brief Initialise the GPIO interrupt handling module */
void gpio_interrupt_init(void);
/**
* \brief Register a GPIO interrupt handler
* \param f Pointer to a handler to be called when an interrupt is raised on
* ioid
* \param ioid Associate \a f with this ioid. \e ioid must be specified with
* its numeric representation (0, 1, .. 31). Defines for these
* numeric representations are IOID_x
*/
void gpio_interrupt_register_handler(uint8_t ioid, gpio_interrupt_handler_t f);
#endif /* GPIO_INTERRUPT_H_ */
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
*/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,623 @@
/******************************************************************************
* Filename: ble_cmd_field.h
* Revised: $ $
* Revision: $ $
*
* Description: CC26xx/CC13xx API for Bluetooth Low Energy commands
*
* Copyright (C) 2015 Texas Instruments Incorporated - http://www.ti.com/
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* Neither the name of Texas Instruments Incorporated 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
* OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
* DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
* THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************/
#ifndef __BLE_CMD_FIELD_H
#define __BLE_CMD_FIELD_H
#include <stdint.h>
#include "mailbox.h"
#include "common_cmd.h"
#define _POSITION_bleRadioOp_channel 14
#define _TYPE_bleRadioOp_channel uint8_t
#define _POSITION_bleRadioOp_whitening 15
#define _TYPE_bleRadioOp_whitening uint8_t
#define _BITPOS_bleRadioOp_whitening_init 0
#define _NBITS_bleRadioOp_whitening_init 7
#define _BITPOS_bleRadioOp_whitening_bOverride 7
#define _NBITS_bleRadioOp_whitening_bOverride 1
#define _POSITION_bleRadioOp_pParams 16
#define _TYPE_bleRadioOp_pParams uint8_t*
#define _POSITION_bleRadioOp_pOutput 20
#define _TYPE_bleRadioOp_pOutput uint8_t*
#define _SIZEOF_bleRadioOp 24
#define _SIZEOF_CMD_BLE_SLAVE 24
#define _SIZEOF_CMD_BLE_MASTER 24
#define _SIZEOF_CMD_BLE_ADV 24
#define _SIZEOF_CMD_BLE_ADV_DIR 24
#define _SIZEOF_CMD_BLE_ADV_NC 24
#define _SIZEOF_CMD_BLE_ADV_SCAN 24
#define _SIZEOF_CMD_BLE_SCANNER 24
#define _SIZEOF_CMD_BLE_INITIATOR 24
#define _SIZEOF_CMD_BLE_GENERIC_RX 24
#define _SIZEOF_CMD_BLE_TX_TEST 24
#define _POSITION_CMD_BLE_ADV_PAYLOAD_payloadType 2
#define _TYPE_CMD_BLE_ADV_PAYLOAD_payloadType uint8_t
#define _POSITION_CMD_BLE_ADV_PAYLOAD_newLen 3
#define _TYPE_CMD_BLE_ADV_PAYLOAD_newLen uint8_t
#define _POSITION_CMD_BLE_ADV_PAYLOAD_pNewData 4
#define _TYPE_CMD_BLE_ADV_PAYLOAD_pNewData uint8_t*
#define _POSITION_CMD_BLE_ADV_PAYLOAD_pParams 8
#define _TYPE_CMD_BLE_ADV_PAYLOAD_pParams uint8_t*
#define _SIZEOF_CMD_BLE_ADV_PAYLOAD 12
#define _POSITION_bleMasterSlavePar_pRxQ 0
#define _TYPE_bleMasterSlavePar_pRxQ dataQueue_t*
#define _POSITION_bleMasterSlavePar_pTxQ 4
#define _TYPE_bleMasterSlavePar_pTxQ dataQueue_t*
#define _POSITION_bleMasterSlavePar_rxConfig 8
#define _TYPE_bleMasterSlavePar_rxConfig uint8_t
#define _BITPOS_bleMasterSlavePar_rxConfig_bAutoFlushIgnored 0
#define _NBITS_bleMasterSlavePar_rxConfig_bAutoFlushIgnored 1
#define _BITPOS_bleMasterSlavePar_rxConfig_bAutoFlushCrcErr 1
#define _NBITS_bleMasterSlavePar_rxConfig_bAutoFlushCrcErr 1
#define _BITPOS_bleMasterSlavePar_rxConfig_bAutoFlushEmpty 2
#define _NBITS_bleMasterSlavePar_rxConfig_bAutoFlushEmpty 1
#define _BITPOS_bleMasterSlavePar_rxConfig_bIncludeLenByte 3
#define _NBITS_bleMasterSlavePar_rxConfig_bIncludeLenByte 1
#define _BITPOS_bleMasterSlavePar_rxConfig_bIncludeCrc 4
#define _NBITS_bleMasterSlavePar_rxConfig_bIncludeCrc 1
#define _BITPOS_bleMasterSlavePar_rxConfig_bAppendRssi 5
#define _NBITS_bleMasterSlavePar_rxConfig_bAppendRssi 1
#define _BITPOS_bleMasterSlavePar_rxConfig_bAppendStatus 6
#define _NBITS_bleMasterSlavePar_rxConfig_bAppendStatus 1
#define _BITPOS_bleMasterSlavePar_rxConfig_bAppendTimestamp 7
#define _NBITS_bleMasterSlavePar_rxConfig_bAppendTimestamp 1
#define _POSITION_bleMasterSlavePar_seqStat 9
#define _TYPE_bleMasterSlavePar_seqStat uint8_t
#define _BITPOS_bleMasterSlavePar_seqStat_lastRxSn 0
#define _NBITS_bleMasterSlavePar_seqStat_lastRxSn 1
#define _BITPOS_bleMasterSlavePar_seqStat_lastTxSn 1
#define _NBITS_bleMasterSlavePar_seqStat_lastTxSn 1
#define _BITPOS_bleMasterSlavePar_seqStat_nextTxSn 2
#define _NBITS_bleMasterSlavePar_seqStat_nextTxSn 1
#define _BITPOS_bleMasterSlavePar_seqStat_bFirstPkt 3
#define _NBITS_bleMasterSlavePar_seqStat_bFirstPkt 1
#define _BITPOS_bleMasterSlavePar_seqStat_bAutoEmpty 4
#define _NBITS_bleMasterSlavePar_seqStat_bAutoEmpty 1
#define _BITPOS_bleMasterSlavePar_seqStat_bLlCtrlTx 5
#define _NBITS_bleMasterSlavePar_seqStat_bLlCtrlTx 1
#define _BITPOS_bleMasterSlavePar_seqStat_bLlCtrlAckRx 6
#define _NBITS_bleMasterSlavePar_seqStat_bLlCtrlAckRx 1
#define _BITPOS_bleMasterSlavePar_seqStat_bLlCtrlAckPending 7
#define _NBITS_bleMasterSlavePar_seqStat_bLlCtrlAckPending 1
#define _POSITION_bleMasterSlavePar_maxNack 10
#define _TYPE_bleMasterSlavePar_maxNack uint8_t
#define _POSITION_bleMasterSlavePar_maxPkt 11
#define _TYPE_bleMasterSlavePar_maxPkt uint8_t
#define _POSITION_bleMasterSlavePar_accessAddress 12
#define _TYPE_bleMasterSlavePar_accessAddress uint32_t
#define _POSITION_bleMasterSlavePar_crcInit0 16
#define _TYPE_bleMasterSlavePar_crcInit0 uint8_t
#define _POSITION_bleMasterSlavePar_crcInit1 17
#define _TYPE_bleMasterSlavePar_crcInit1 uint8_t
#define _POSITION_bleMasterSlavePar_crcInit2 18
#define _TYPE_bleMasterSlavePar_crcInit2 uint8_t
#define _POSITION_bleMasterSlavePar_crcInit 16
#define _TYPE_bleMasterSlavePar_crcInit uint32_t
#define _SIZEOF_bleMasterSlavePar 20
#define _POSITION_bleMasterPar_endTrigger 19
#define _TYPE_bleMasterPar_endTrigger uint8_t
#define _BITPOS_bleMasterPar_endTrigger_triggerType 0
#define _NBITS_bleMasterPar_endTrigger_triggerType 4
#define _BITPOS_bleMasterPar_endTrigger_bEnaCmd 4
#define _NBITS_bleMasterPar_endTrigger_bEnaCmd 1
#define _BITPOS_bleMasterPar_endTrigger_triggerNo 5
#define _NBITS_bleMasterPar_endTrigger_triggerNo 2
#define _BITPOS_bleMasterPar_endTrigger_pastTrig 7
#define _NBITS_bleMasterPar_endTrigger_pastTrig 1
#define _POSITION_bleMasterPar_endTime 20
#define _TYPE_bleMasterPar_endTime ratmr_t
#define _SIZEOF_bleMasterPar 24
#define _POSITION_bleSlavePar_timeoutTrigger 19
#define _TYPE_bleSlavePar_timeoutTrigger uint8_t
#define _BITPOS_bleSlavePar_timeoutTrigger_triggerType 0
#define _NBITS_bleSlavePar_timeoutTrigger_triggerType 4
#define _BITPOS_bleSlavePar_timeoutTrigger_bEnaCmd 4
#define _NBITS_bleSlavePar_timeoutTrigger_bEnaCmd 1
#define _BITPOS_bleSlavePar_timeoutTrigger_triggerNo 5
#define _NBITS_bleSlavePar_timeoutTrigger_triggerNo 2
#define _BITPOS_bleSlavePar_timeoutTrigger_pastTrig 7
#define _NBITS_bleSlavePar_timeoutTrigger_pastTrig 1
#define _POSITION_bleSlavePar_timeoutTime 20
#define _TYPE_bleSlavePar_timeoutTime ratmr_t
#define _POSITION_bleSlavePar_endTrigger 27
#define _TYPE_bleSlavePar_endTrigger uint8_t
#define _BITPOS_bleSlavePar_endTrigger_triggerType 0
#define _NBITS_bleSlavePar_endTrigger_triggerType 4
#define _BITPOS_bleSlavePar_endTrigger_bEnaCmd 4
#define _NBITS_bleSlavePar_endTrigger_bEnaCmd 1
#define _BITPOS_bleSlavePar_endTrigger_triggerNo 5
#define _NBITS_bleSlavePar_endTrigger_triggerNo 2
#define _BITPOS_bleSlavePar_endTrigger_pastTrig 7
#define _NBITS_bleSlavePar_endTrigger_pastTrig 1
#define _POSITION_bleSlavePar_endTime 28
#define _TYPE_bleSlavePar_endTime ratmr_t
#define _SIZEOF_bleSlavePar 32
#define _POSITION_bleAdvPar_pRxQ 0
#define _TYPE_bleAdvPar_pRxQ dataQueue_t*
#define _POSITION_bleAdvPar_rxConfig 4
#define _TYPE_bleAdvPar_rxConfig uint8_t
#define _BITPOS_bleAdvPar_rxConfig_bAutoFlushIgnored 0
#define _NBITS_bleAdvPar_rxConfig_bAutoFlushIgnored 1
#define _BITPOS_bleAdvPar_rxConfig_bAutoFlushCrcErr 1
#define _NBITS_bleAdvPar_rxConfig_bAutoFlushCrcErr 1
#define _BITPOS_bleAdvPar_rxConfig_bAutoFlushEmpty 2
#define _NBITS_bleAdvPar_rxConfig_bAutoFlushEmpty 1
#define _BITPOS_bleAdvPar_rxConfig_bIncludeLenByte 3
#define _NBITS_bleAdvPar_rxConfig_bIncludeLenByte 1
#define _BITPOS_bleAdvPar_rxConfig_bIncludeCrc 4
#define _NBITS_bleAdvPar_rxConfig_bIncludeCrc 1
#define _BITPOS_bleAdvPar_rxConfig_bAppendRssi 5
#define _NBITS_bleAdvPar_rxConfig_bAppendRssi 1
#define _BITPOS_bleAdvPar_rxConfig_bAppendStatus 6
#define _NBITS_bleAdvPar_rxConfig_bAppendStatus 1
#define _BITPOS_bleAdvPar_rxConfig_bAppendTimestamp 7
#define _NBITS_bleAdvPar_rxConfig_bAppendTimestamp 1
#define _POSITION_bleAdvPar_advConfig 5
#define _TYPE_bleAdvPar_advConfig uint8_t
#define _BITPOS_bleAdvPar_advConfig_advFilterPolicy 0
#define _NBITS_bleAdvPar_advConfig_advFilterPolicy 2
#define _BITPOS_bleAdvPar_advConfig_deviceAddrType 2
#define _NBITS_bleAdvPar_advConfig_deviceAddrType 1
#define _BITPOS_bleAdvPar_advConfig_peerAddrType 3
#define _NBITS_bleAdvPar_advConfig_peerAddrType 1
#define _BITPOS_bleAdvPar_advConfig_bStrictLenFilter 4
#define _NBITS_bleAdvPar_advConfig_bStrictLenFilter 1
#define _POSITION_bleAdvPar_advLen 6
#define _TYPE_bleAdvPar_advLen uint8_t
#define _POSITION_bleAdvPar_scanRspLen 7
#define _TYPE_bleAdvPar_scanRspLen uint8_t
#define _POSITION_bleAdvPar_pAdvData 8
#define _TYPE_bleAdvPar_pAdvData uint8_t*
#define _POSITION_bleAdvPar_pScanRspData 12
#define _TYPE_bleAdvPar_pScanRspData uint8_t*
#define _POSITION_bleAdvPar_pDeviceAddress 16
#define _TYPE_bleAdvPar_pDeviceAddress uint16_t*
#define _POSITION_bleAdvPar_pWhiteList 20
#define _TYPE_bleAdvPar_pWhiteList uint32_t*
#define _POSITION_bleAdvPar_endTrigger 27
#define _TYPE_bleAdvPar_endTrigger uint8_t
#define _BITPOS_bleAdvPar_endTrigger_triggerType 0
#define _NBITS_bleAdvPar_endTrigger_triggerType 4
#define _BITPOS_bleAdvPar_endTrigger_bEnaCmd 4
#define _NBITS_bleAdvPar_endTrigger_bEnaCmd 1
#define _BITPOS_bleAdvPar_endTrigger_triggerNo 5
#define _NBITS_bleAdvPar_endTrigger_triggerNo 2
#define _BITPOS_bleAdvPar_endTrigger_pastTrig 7
#define _NBITS_bleAdvPar_endTrigger_pastTrig 1
#define _POSITION_bleAdvPar_endTime 28
#define _TYPE_bleAdvPar_endTime ratmr_t
#define _SIZEOF_bleAdvPar 32
#define _POSITION_bleScannerPar_pRxQ 0
#define _TYPE_bleScannerPar_pRxQ dataQueue_t*
#define _POSITION_bleScannerPar_rxConfig 4
#define _TYPE_bleScannerPar_rxConfig uint8_t
#define _BITPOS_bleScannerPar_rxConfig_bAutoFlushIgnored 0
#define _NBITS_bleScannerPar_rxConfig_bAutoFlushIgnored 1
#define _BITPOS_bleScannerPar_rxConfig_bAutoFlushCrcErr 1
#define _NBITS_bleScannerPar_rxConfig_bAutoFlushCrcErr 1
#define _BITPOS_bleScannerPar_rxConfig_bAutoFlushEmpty 2
#define _NBITS_bleScannerPar_rxConfig_bAutoFlushEmpty 1
#define _BITPOS_bleScannerPar_rxConfig_bIncludeLenByte 3
#define _NBITS_bleScannerPar_rxConfig_bIncludeLenByte 1
#define _BITPOS_bleScannerPar_rxConfig_bIncludeCrc 4
#define _NBITS_bleScannerPar_rxConfig_bIncludeCrc 1
#define _BITPOS_bleScannerPar_rxConfig_bAppendRssi 5
#define _NBITS_bleScannerPar_rxConfig_bAppendRssi 1
#define _BITPOS_bleScannerPar_rxConfig_bAppendStatus 6
#define _NBITS_bleScannerPar_rxConfig_bAppendStatus 1
#define _BITPOS_bleScannerPar_rxConfig_bAppendTimestamp 7
#define _NBITS_bleScannerPar_rxConfig_bAppendTimestamp 1
#define _POSITION_bleScannerPar_scanConfig 5
#define _TYPE_bleScannerPar_scanConfig uint8_t
#define _BITPOS_bleScannerPar_scanConfig_scanFilterPolicy 0
#define _NBITS_bleScannerPar_scanConfig_scanFilterPolicy 1
#define _BITPOS_bleScannerPar_scanConfig_bActiveScan 1
#define _NBITS_bleScannerPar_scanConfig_bActiveScan 1
#define _BITPOS_bleScannerPar_scanConfig_deviceAddrType 2
#define _NBITS_bleScannerPar_scanConfig_deviceAddrType 1
#define _BITPOS_bleScannerPar_scanConfig_bStrictLenFilter 4
#define _NBITS_bleScannerPar_scanConfig_bStrictLenFilter 1
#define _BITPOS_bleScannerPar_scanConfig_bAutoWlIgnore 5
#define _NBITS_bleScannerPar_scanConfig_bAutoWlIgnore 1
#define _BITPOS_bleScannerPar_scanConfig_bEndOnRpt 6
#define _NBITS_bleScannerPar_scanConfig_bEndOnRpt 1
#define _POSITION_bleScannerPar_randomState 6
#define _TYPE_bleScannerPar_randomState uint16_t
#define _POSITION_bleScannerPar_backoffCount 8
#define _TYPE_bleScannerPar_backoffCount uint16_t
#define _POSITION_bleScannerPar_backoffPar 10
#define _TYPE_bleScannerPar_backoffPar uint8_t
#define _BITPOS_bleScannerPar_backoffPar_logUpperLimit 0
#define _NBITS_bleScannerPar_backoffPar_logUpperLimit 4
#define _BITPOS_bleScannerPar_backoffPar_bLastSucceeded 4
#define _NBITS_bleScannerPar_backoffPar_bLastSucceeded 1
#define _BITPOS_bleScannerPar_backoffPar_bLastFailed 5
#define _NBITS_bleScannerPar_backoffPar_bLastFailed 1
#define _POSITION_bleScannerPar_scanReqLen 11
#define _TYPE_bleScannerPar_scanReqLen uint8_t
#define _POSITION_bleScannerPar_pScanReqData 12
#define _TYPE_bleScannerPar_pScanReqData uint8_t*
#define _POSITION_bleScannerPar_pDeviceAddress 16
#define _TYPE_bleScannerPar_pDeviceAddress uint16_t*
#define _POSITION_bleScannerPar_pWhiteList 20
#define _TYPE_bleScannerPar_pWhiteList uint32_t*
#define _POSITION_bleScannerPar_timeoutTrigger 26
#define _TYPE_bleScannerPar_timeoutTrigger uint8_t
#define _BITPOS_bleScannerPar_timeoutTrigger_triggerType 0
#define _NBITS_bleScannerPar_timeoutTrigger_triggerType 4
#define _BITPOS_bleScannerPar_timeoutTrigger_bEnaCmd 4
#define _NBITS_bleScannerPar_timeoutTrigger_bEnaCmd 1
#define _BITPOS_bleScannerPar_timeoutTrigger_triggerNo 5
#define _NBITS_bleScannerPar_timeoutTrigger_triggerNo 2
#define _BITPOS_bleScannerPar_timeoutTrigger_pastTrig 7
#define _NBITS_bleScannerPar_timeoutTrigger_pastTrig 1
#define _POSITION_bleScannerPar_endTrigger 27
#define _TYPE_bleScannerPar_endTrigger uint8_t
#define _BITPOS_bleScannerPar_endTrigger_triggerType 0
#define _NBITS_bleScannerPar_endTrigger_triggerType 4
#define _BITPOS_bleScannerPar_endTrigger_bEnaCmd 4
#define _NBITS_bleScannerPar_endTrigger_bEnaCmd 1
#define _BITPOS_bleScannerPar_endTrigger_triggerNo 5
#define _NBITS_bleScannerPar_endTrigger_triggerNo 2
#define _BITPOS_bleScannerPar_endTrigger_pastTrig 7
#define _NBITS_bleScannerPar_endTrigger_pastTrig 1
#define _POSITION_bleScannerPar_timeoutTime 28
#define _TYPE_bleScannerPar_timeoutTime ratmr_t
#define _POSITION_bleScannerPar_endTime 32
#define _TYPE_bleScannerPar_endTime ratmr_t
#define _SIZEOF_bleScannerPar 36
#define _POSITION_bleInitiatorPar_pRxQ 0
#define _TYPE_bleInitiatorPar_pRxQ dataQueue_t*
#define _POSITION_bleInitiatorPar_rxConfig 4
#define _TYPE_bleInitiatorPar_rxConfig uint8_t
#define _BITPOS_bleInitiatorPar_rxConfig_bAutoFlushIgnored 0
#define _NBITS_bleInitiatorPar_rxConfig_bAutoFlushIgnored 1
#define _BITPOS_bleInitiatorPar_rxConfig_bAutoFlushCrcErr 1
#define _NBITS_bleInitiatorPar_rxConfig_bAutoFlushCrcErr 1
#define _BITPOS_bleInitiatorPar_rxConfig_bAutoFlushEmpty 2
#define _NBITS_bleInitiatorPar_rxConfig_bAutoFlushEmpty 1
#define _BITPOS_bleInitiatorPar_rxConfig_bIncludeLenByte 3
#define _NBITS_bleInitiatorPar_rxConfig_bIncludeLenByte 1
#define _BITPOS_bleInitiatorPar_rxConfig_bIncludeCrc 4
#define _NBITS_bleInitiatorPar_rxConfig_bIncludeCrc 1
#define _BITPOS_bleInitiatorPar_rxConfig_bAppendRssi 5
#define _NBITS_bleInitiatorPar_rxConfig_bAppendRssi 1
#define _BITPOS_bleInitiatorPar_rxConfig_bAppendStatus 6
#define _NBITS_bleInitiatorPar_rxConfig_bAppendStatus 1
#define _BITPOS_bleInitiatorPar_rxConfig_bAppendTimestamp 7
#define _NBITS_bleInitiatorPar_rxConfig_bAppendTimestamp 1
#define _POSITION_bleInitiatorPar_initConfig 5
#define _TYPE_bleInitiatorPar_initConfig uint8_t
#define _BITPOS_bleInitiatorPar_initConfig_bUseWhiteList 0
#define _NBITS_bleInitiatorPar_initConfig_bUseWhiteList 1
#define _BITPOS_bleInitiatorPar_initConfig_bDynamicWinOffset 1
#define _NBITS_bleInitiatorPar_initConfig_bDynamicWinOffset 1
#define _BITPOS_bleInitiatorPar_initConfig_deviceAddrType 2
#define _NBITS_bleInitiatorPar_initConfig_deviceAddrType 1
#define _BITPOS_bleInitiatorPar_initConfig_peerAddrType 3
#define _NBITS_bleInitiatorPar_initConfig_peerAddrType 1
#define _BITPOS_bleInitiatorPar_initConfig_bStrictLenFilter 4
#define _NBITS_bleInitiatorPar_initConfig_bStrictLenFilter 1
#define _POSITION_bleInitiatorPar_connectReqLen 7
#define _TYPE_bleInitiatorPar_connectReqLen uint8_t
#define _POSITION_bleInitiatorPar_pConnectReqData 8
#define _TYPE_bleInitiatorPar_pConnectReqData uint8_t*
#define _POSITION_bleInitiatorPar_pDeviceAddress 12
#define _TYPE_bleInitiatorPar_pDeviceAddress uint16_t*
#define _POSITION_bleInitiatorPar_pWhiteList 16
#define _TYPE_bleInitiatorPar_pWhiteList uint32_t*
#define _POSITION_bleInitiatorPar_connectTime 20
#define _TYPE_bleInitiatorPar_connectTime ratmr_t
#define _POSITION_bleInitiatorPar_timeoutTrigger 26
#define _TYPE_bleInitiatorPar_timeoutTrigger uint8_t
#define _BITPOS_bleInitiatorPar_timeoutTrigger_triggerType 0
#define _NBITS_bleInitiatorPar_timeoutTrigger_triggerType 4
#define _BITPOS_bleInitiatorPar_timeoutTrigger_bEnaCmd 4
#define _NBITS_bleInitiatorPar_timeoutTrigger_bEnaCmd 1
#define _BITPOS_bleInitiatorPar_timeoutTrigger_triggerNo 5
#define _NBITS_bleInitiatorPar_timeoutTrigger_triggerNo 2
#define _BITPOS_bleInitiatorPar_timeoutTrigger_pastTrig 7
#define _NBITS_bleInitiatorPar_timeoutTrigger_pastTrig 1
#define _POSITION_bleInitiatorPar_endTrigger 27
#define _TYPE_bleInitiatorPar_endTrigger uint8_t
#define _BITPOS_bleInitiatorPar_endTrigger_triggerType 0
#define _NBITS_bleInitiatorPar_endTrigger_triggerType 4
#define _BITPOS_bleInitiatorPar_endTrigger_bEnaCmd 4
#define _NBITS_bleInitiatorPar_endTrigger_bEnaCmd 1
#define _BITPOS_bleInitiatorPar_endTrigger_triggerNo 5
#define _NBITS_bleInitiatorPar_endTrigger_triggerNo 2
#define _BITPOS_bleInitiatorPar_endTrigger_pastTrig 7
#define _NBITS_bleInitiatorPar_endTrigger_pastTrig 1
#define _POSITION_bleInitiatorPar_timeoutTime 28
#define _TYPE_bleInitiatorPar_timeoutTime ratmr_t
#define _POSITION_bleInitiatorPar_endTime 32
#define _TYPE_bleInitiatorPar_endTime ratmr_t
#define _SIZEOF_bleInitiatorPar 36
#define _POSITION_bleGenericRxPar_pRxQ 0
#define _TYPE_bleGenericRxPar_pRxQ dataQueue_t*
#define _POSITION_bleGenericRxPar_rxConfig 4
#define _TYPE_bleGenericRxPar_rxConfig uint8_t
#define _BITPOS_bleGenericRxPar_rxConfig_bAutoFlushIgnored 0
#define _NBITS_bleGenericRxPar_rxConfig_bAutoFlushIgnored 1
#define _BITPOS_bleGenericRxPar_rxConfig_bAutoFlushCrcErr 1
#define _NBITS_bleGenericRxPar_rxConfig_bAutoFlushCrcErr 1
#define _BITPOS_bleGenericRxPar_rxConfig_bAutoFlushEmpty 2
#define _NBITS_bleGenericRxPar_rxConfig_bAutoFlushEmpty 1
#define _BITPOS_bleGenericRxPar_rxConfig_bIncludeLenByte 3
#define _NBITS_bleGenericRxPar_rxConfig_bIncludeLenByte 1
#define _BITPOS_bleGenericRxPar_rxConfig_bIncludeCrc 4
#define _NBITS_bleGenericRxPar_rxConfig_bIncludeCrc 1
#define _BITPOS_bleGenericRxPar_rxConfig_bAppendRssi 5
#define _NBITS_bleGenericRxPar_rxConfig_bAppendRssi 1
#define _BITPOS_bleGenericRxPar_rxConfig_bAppendStatus 6
#define _NBITS_bleGenericRxPar_rxConfig_bAppendStatus 1
#define _BITPOS_bleGenericRxPar_rxConfig_bAppendTimestamp 7
#define _NBITS_bleGenericRxPar_rxConfig_bAppendTimestamp 1
#define _POSITION_bleGenericRxPar_bRepeat 5
#define _TYPE_bleGenericRxPar_bRepeat uint8_t
#define _POSITION_bleGenericRxPar_accessAddress 8
#define _TYPE_bleGenericRxPar_accessAddress uint32_t
#define _POSITION_bleGenericRxPar_crcInit0 12
#define _TYPE_bleGenericRxPar_crcInit0 uint8_t
#define _POSITION_bleGenericRxPar_crcInit1 13
#define _TYPE_bleGenericRxPar_crcInit1 uint8_t
#define _POSITION_bleGenericRxPar_crcInit2 14
#define _TYPE_bleGenericRxPar_crcInit2 uint8_t
#define _POSITION_bleGenericRxPar_crcInit 12
#define _TYPE_bleGenericRxPar_crcInit uint32_t
#define _POSITION_bleGenericRxPar_endTrigger 15
#define _TYPE_bleGenericRxPar_endTrigger uint8_t
#define _BITPOS_bleGenericRxPar_endTrigger_triggerType 0
#define _NBITS_bleGenericRxPar_endTrigger_triggerType 4
#define _BITPOS_bleGenericRxPar_endTrigger_bEnaCmd 4
#define _NBITS_bleGenericRxPar_endTrigger_bEnaCmd 1
#define _BITPOS_bleGenericRxPar_endTrigger_triggerNo 5
#define _NBITS_bleGenericRxPar_endTrigger_triggerNo 2
#define _BITPOS_bleGenericRxPar_endTrigger_pastTrig 7
#define _NBITS_bleGenericRxPar_endTrigger_pastTrig 1
#define _POSITION_bleGenericRxPar_endTime 16
#define _TYPE_bleGenericRxPar_endTime ratmr_t
#define _SIZEOF_bleGenericRxPar 20
#define _POSITION_bleTxTestPar_numPackets 0
#define _TYPE_bleTxTestPar_numPackets uint16_t
#define _POSITION_bleTxTestPar_payloadLength 2
#define _TYPE_bleTxTestPar_payloadLength uint8_t
#define _POSITION_bleTxTestPar_packetType 3
#define _TYPE_bleTxTestPar_packetType uint8_t
#define _POSITION_bleTxTestPar_period 4
#define _TYPE_bleTxTestPar_period ratmr_t
#define _POSITION_bleTxTestPar_config 8
#define _TYPE_bleTxTestPar_config uint8_t
#define _BITPOS_bleTxTestPar_config_bOverrideDefault 0
#define _NBITS_bleTxTestPar_config_bOverrideDefault 1
#define _BITPOS_bleTxTestPar_config_bUsePrbs9 1
#define _NBITS_bleTxTestPar_config_bUsePrbs9 1
#define _BITPOS_bleTxTestPar_config_bUsePrbs15 2
#define _NBITS_bleTxTestPar_config_bUsePrbs15 1
#define _POSITION_bleTxTestPar_byteVal 9
#define _TYPE_bleTxTestPar_byteVal uint8_t
#define _POSITION_bleTxTestPar_endTrigger 11
#define _TYPE_bleTxTestPar_endTrigger uint8_t
#define _BITPOS_bleTxTestPar_endTrigger_triggerType 0
#define _NBITS_bleTxTestPar_endTrigger_triggerType 4
#define _BITPOS_bleTxTestPar_endTrigger_bEnaCmd 4
#define _NBITS_bleTxTestPar_endTrigger_bEnaCmd 1
#define _BITPOS_bleTxTestPar_endTrigger_triggerNo 5
#define _NBITS_bleTxTestPar_endTrigger_triggerNo 2
#define _BITPOS_bleTxTestPar_endTrigger_pastTrig 7
#define _NBITS_bleTxTestPar_endTrigger_pastTrig 1
#define _POSITION_bleTxTestPar_endTime 12
#define _TYPE_bleTxTestPar_endTime ratmr_t
#define _SIZEOF_bleTxTestPar 16
#define _POSITION_bleMasterSlaveOutput_nTx 0
#define _TYPE_bleMasterSlaveOutput_nTx uint8_t
#define _POSITION_bleMasterSlaveOutput_nTxAck 1
#define _TYPE_bleMasterSlaveOutput_nTxAck uint8_t
#define _POSITION_bleMasterSlaveOutput_nTxCtrl 2
#define _TYPE_bleMasterSlaveOutput_nTxCtrl uint8_t
#define _POSITION_bleMasterSlaveOutput_nTxCtrlAck 3
#define _TYPE_bleMasterSlaveOutput_nTxCtrlAck uint8_t
#define _POSITION_bleMasterSlaveOutput_nTxCtrlAckAck 4
#define _TYPE_bleMasterSlaveOutput_nTxCtrlAckAck uint8_t
#define _POSITION_bleMasterSlaveOutput_nTxRetrans 5
#define _TYPE_bleMasterSlaveOutput_nTxRetrans uint8_t
#define _POSITION_bleMasterSlaveOutput_nTxEntryDone 6
#define _TYPE_bleMasterSlaveOutput_nTxEntryDone uint8_t
#define _POSITION_bleMasterSlaveOutput_nRxOk 7
#define _TYPE_bleMasterSlaveOutput_nRxOk uint8_t
#define _POSITION_bleMasterSlaveOutput_nRxCtrl 8
#define _TYPE_bleMasterSlaveOutput_nRxCtrl uint8_t
#define _POSITION_bleMasterSlaveOutput_nRxCtrlAck 9
#define _TYPE_bleMasterSlaveOutput_nRxCtrlAck uint8_t
#define _POSITION_bleMasterSlaveOutput_nRxNok 10
#define _TYPE_bleMasterSlaveOutput_nRxNok uint8_t
#define _POSITION_bleMasterSlaveOutput_nRxIgnored 11
#define _TYPE_bleMasterSlaveOutput_nRxIgnored uint8_t
#define _POSITION_bleMasterSlaveOutput_nRxEmpty 12
#define _TYPE_bleMasterSlaveOutput_nRxEmpty uint8_t
#define _POSITION_bleMasterSlaveOutput_nRxBufFull 13
#define _TYPE_bleMasterSlaveOutput_nRxBufFull uint8_t
#define _POSITION_bleMasterSlaveOutput_lastRssi 14
#define _TYPE_bleMasterSlaveOutput_lastRssi int8_t
#define _POSITION_bleMasterSlaveOutput_pktStatus 15
#define _TYPE_bleMasterSlaveOutput_pktStatus uint8_t
#define _BITPOS_bleMasterSlaveOutput_pktStatus_bTimeStampValid 0
#define _NBITS_bleMasterSlaveOutput_pktStatus_bTimeStampValid 1
#define _BITPOS_bleMasterSlaveOutput_pktStatus_bLastCrcErr 1
#define _NBITS_bleMasterSlaveOutput_pktStatus_bLastCrcErr 1
#define _BITPOS_bleMasterSlaveOutput_pktStatus_bLastIgnored 2
#define _NBITS_bleMasterSlaveOutput_pktStatus_bLastIgnored 1
#define _BITPOS_bleMasterSlaveOutput_pktStatus_bLastEmpty 3
#define _NBITS_bleMasterSlaveOutput_pktStatus_bLastEmpty 1
#define _BITPOS_bleMasterSlaveOutput_pktStatus_bLastCtrl 4
#define _NBITS_bleMasterSlaveOutput_pktStatus_bLastCtrl 1
#define _BITPOS_bleMasterSlaveOutput_pktStatus_bLastMd 5
#define _NBITS_bleMasterSlaveOutput_pktStatus_bLastMd 1
#define _BITPOS_bleMasterSlaveOutput_pktStatus_bLastAck 6
#define _NBITS_bleMasterSlaveOutput_pktStatus_bLastAck 1
#define _POSITION_bleMasterSlaveOutput_timeStamp 16
#define _TYPE_bleMasterSlaveOutput_timeStamp ratmr_t
#define _SIZEOF_bleMasterSlaveOutput 20
#define _POSITION_bleAdvOutput_nTxAdvInd 0
#define _TYPE_bleAdvOutput_nTxAdvInd uint16_t
#define _POSITION_bleAdvOutput_nTxScanRsp 2
#define _TYPE_bleAdvOutput_nTxScanRsp uint8_t
#define _POSITION_bleAdvOutput_nRxScanReq 3
#define _TYPE_bleAdvOutput_nRxScanReq uint8_t
#define _POSITION_bleAdvOutput_nRxConnectReq 4
#define _TYPE_bleAdvOutput_nRxConnectReq uint8_t
#define _POSITION_bleAdvOutput_nRxNok 6
#define _TYPE_bleAdvOutput_nRxNok uint16_t
#define _POSITION_bleAdvOutput_nRxIgnored 8
#define _TYPE_bleAdvOutput_nRxIgnored uint16_t
#define _POSITION_bleAdvOutput_nRxBufFull 10
#define _TYPE_bleAdvOutput_nRxBufFull uint8_t
#define _POSITION_bleAdvOutput_lastRssi 11
#define _TYPE_bleAdvOutput_lastRssi int8_t
#define _POSITION_bleAdvOutput_timeStamp 12
#define _TYPE_bleAdvOutput_timeStamp ratmr_t
#define _SIZEOF_bleAdvOutput 16
#define _POSITION_bleScannerOutput_nTxScanReq 0
#define _TYPE_bleScannerOutput_nTxScanReq uint16_t
#define _POSITION_bleScannerOutput_nBackedOffScanReq 2
#define _TYPE_bleScannerOutput_nBackedOffScanReq uint16_t
#define _POSITION_bleScannerOutput_nRxAdvOk 4
#define _TYPE_bleScannerOutput_nRxAdvOk uint16_t
#define _POSITION_bleScannerOutput_nRxAdvIgnored 6
#define _TYPE_bleScannerOutput_nRxAdvIgnored uint16_t
#define _POSITION_bleScannerOutput_nRxAdvNok 8
#define _TYPE_bleScannerOutput_nRxAdvNok uint16_t
#define _POSITION_bleScannerOutput_nRxScanRspOk 10
#define _TYPE_bleScannerOutput_nRxScanRspOk uint16_t
#define _POSITION_bleScannerOutput_nRxScanRspIgnored 12
#define _TYPE_bleScannerOutput_nRxScanRspIgnored uint16_t
#define _POSITION_bleScannerOutput_nRxScanRspNok 14
#define _TYPE_bleScannerOutput_nRxScanRspNok uint16_t
#define _POSITION_bleScannerOutput_nRxAdvBufFull 16
#define _TYPE_bleScannerOutput_nRxAdvBufFull uint8_t
#define _POSITION_bleScannerOutput_nRxScanRspBufFull 17
#define _TYPE_bleScannerOutput_nRxScanRspBufFull uint8_t
#define _POSITION_bleScannerOutput_lastRssi 18
#define _TYPE_bleScannerOutput_lastRssi int8_t
#define _POSITION_bleScannerOutput_timeStamp 20
#define _TYPE_bleScannerOutput_timeStamp ratmr_t
#define _SIZEOF_bleScannerOutput 24
#define _POSITION_bleInitiatorOutput_nTxConnectReq 0
#define _TYPE_bleInitiatorOutput_nTxConnectReq uint8_t
#define _POSITION_bleInitiatorOutput_nRxAdvOk 1
#define _TYPE_bleInitiatorOutput_nRxAdvOk uint8_t
#define _POSITION_bleInitiatorOutput_nRxAdvIgnored 2
#define _TYPE_bleInitiatorOutput_nRxAdvIgnored uint16_t
#define _POSITION_bleInitiatorOutput_nRxAdvNok 4
#define _TYPE_bleInitiatorOutput_nRxAdvNok uint16_t
#define _POSITION_bleInitiatorOutput_nRxAdvBufFull 6
#define _TYPE_bleInitiatorOutput_nRxAdvBufFull uint8_t
#define _POSITION_bleInitiatorOutput_lastRssi 7
#define _TYPE_bleInitiatorOutput_lastRssi int8_t
#define _POSITION_bleInitiatorOutput_timeStamp 8
#define _TYPE_bleInitiatorOutput_timeStamp ratmr_t
#define _SIZEOF_bleInitiatorOutput 12
#define _POSITION_bleGenericRxOutput_nRxOk 0
#define _TYPE_bleGenericRxOutput_nRxOk uint16_t
#define _POSITION_bleGenericRxOutput_nRxNok 2
#define _TYPE_bleGenericRxOutput_nRxNok uint16_t
#define _POSITION_bleGenericRxOutput_nRxBufFull 4
#define _TYPE_bleGenericRxOutput_nRxBufFull uint16_t
#define _POSITION_bleGenericRxOutput_lastRssi 6
#define _TYPE_bleGenericRxOutput_lastRssi int8_t
#define _POSITION_bleGenericRxOutput_timeStamp 8
#define _TYPE_bleGenericRxOutput_timeStamp ratmr_t
#define _SIZEOF_bleGenericRxOutput 12
#define _POSITION_bleTxTestOutput_nTx 0
#define _TYPE_bleTxTestOutput_nTx uint16_t
#define _SIZEOF_bleTxTestOutput 2
#define _POSITION_bleWhiteListEntry_size 0
#define _TYPE_bleWhiteListEntry_size uint8_t
#define _POSITION_bleWhiteListEntry_conf 1
#define _TYPE_bleWhiteListEntry_conf uint8_t
#define _BITPOS_bleWhiteListEntry_conf_bEnable 0
#define _NBITS_bleWhiteListEntry_conf_bEnable 1
#define _BITPOS_bleWhiteListEntry_conf_addrType 1
#define _NBITS_bleWhiteListEntry_conf_addrType 1
#define _BITPOS_bleWhiteListEntry_conf_bWlIgn 2
#define _NBITS_bleWhiteListEntry_conf_bWlIgn 1
#define _POSITION_bleWhiteListEntry_address 2
#define _TYPE_bleWhiteListEntry_address uint16_t
#define _POSITION_bleWhiteListEntry_addressHi 4
#define _TYPE_bleWhiteListEntry_addressHi uint32_t
#define _SIZEOF_bleWhiteListEntry 8
#define _POSITION_bleRxStatus_status 0
#define _TYPE_bleRxStatus_status uint8_t
#define _BITPOS_bleRxStatus_status_channel 0
#define _NBITS_bleRxStatus_status_channel 6
#define _BITPOS_bleRxStatus_status_bIgnore 6
#define _NBITS_bleRxStatus_status_bIgnore 1
#define _BITPOS_bleRxStatus_status_bCrcErr 7
#define _NBITS_bleRxStatus_status_bCrcErr 1
#define _SIZEOF_bleRxStatus 1
#endif

View File

@ -0,0 +1,119 @@
/******************************************************************************
* Filename: ble_mailbox.h
* Revised: $ $
* Revision: $ $
*
* Description: Definitions for BLE interface
*
* Copyright (C) 2015 Texas Instruments Incorporated - http://www.ti.com/
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* Neither the name of Texas Instruments Incorporated 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
* OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
* DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
* THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************/
#ifndef _BLE_MAILBOX_H
#define _BLE_MAILBOX_H
#include "mailbox.h"
/// \name CPE interrupt definitions for BLE
/// Interrupt masks for the CPE interrupt in RDBELL. These are new names for interrupts in mailbox.h,
/// used for compartibility with previous versions with separate interrupt numbers.
///@{
#define IRQN_BLE_TX_DONE IRQN_TX_DONE
#define IRQN_BLE_TX_ACK IRQN_TX_ACK
#define IRQN_BLE_TX_CTRL IRQN_TX_CTRL
#define IRQN_BLE_TX_CTRL_ACK IRQN_TX_CTRL_ACK
#define IRQN_BLE_TX_CTRL_ACK_ACK IRQN_TX_CTRL_ACK_ACK
#define IRQN_BLE_TX_RETRANS IRQN_TX_RETRANS
#define IRQN_BLE_TX_ENTRY_DONE IRQN_TX_ENTRY_DONE
#define IRQN_BLE_TX_BUFFER_CHANGED IRQN_TX_BUFFER_CHANGED
#define IRQN_BLE_RX_OK IRQN_RX_OK
#define IRQN_BLE_RX_NOK IRQN_RX_NOK
#define IRQN_BLE_RX_IGNORED IRQN_RX_IGNORED
#define IRQN_BLE_RX_EMPTY IRQN_RX_EMPTY
#define IRQN_BLE_RX_CTRL IRQN_RX_CTRL
#define IRQN_BLE_RX_CTRL_ACK IRQN_RX_CTRL_ACK
#define IRQN_BLE_RX_BUF_FULL IRQN_RX_BUF_FULL
#define IRQN_BLE_RX_ENTRY_DONE IRQN_RX_ENTRY_DONE
#define IRQ_BLE_TX_DONE (1U << IRQN_BLE_TX_DONE)
#define IRQ_BLE_TX_ACK (1U << IRQN_BLE_TX_ACK)
#define IRQ_BLE_TX_CTRL (1U << IRQN_BLE_TX_CTRL)
#define IRQ_BLE_TX_CTRL_ACK (1U << IRQN_BLE_TX_CTRL_ACK)
#define IRQ_BLE_TX_CTRL_ACK_ACK (1U << IRQN_BLE_TX_CTRL_ACK_ACK)
#define IRQ_BLE_TX_RETRANS (1U << IRQN_BLE_TX_RETRANS)
#define IRQ_BLE_TX_ENTRY_DONE (1U << IRQN_BLE_TX_ENTRY_DONE)
#define IRQ_BLE_TX_BUFFER_CHANGED (1U << IRQN_BLE_TX_BUFFER_CHANGED)
#define IRQ_BLE_RX_OK (1U << IRQN_BLE_RX_OK)
#define IRQ_BLE_RX_NOK (1U << IRQN_BLE_RX_NOK)
#define IRQ_BLE_RX_IGNORED (1U << IRQN_BLE_RX_IGNORED)
#define IRQ_BLE_RX_EMPTY (1U << IRQN_BLE_RX_EMPTY)
#define IRQ_BLE_RX_CTRL (1U << IRQN_BLE_RX_CTRL)
#define IRQ_BLE_RX_CTRL_ACK (1U << IRQN_BLE_RX_CTRL_ACK)
#define IRQ_BLE_RX_BUF_FULL (1U << IRQN_BLE_RX_BUF_FULL)
#define IRQ_BLE_RX_ENTRY_DONE (1U << IRQN_BLE_RX_ENTRY_DONE)
///@}
/// \name Radio operation status
/// Radio operation status format:
/// Bits 15:12: Protocol
/// 0001: BLE
/// Bits 11:10: Type
/// 00: Not finished
/// 01: Done successfully
/// 10: Done with error
/// Bits 9:0: Identifier
/// \name Operation finished normally
///@{
#define BLE_DONE_OK 0x1400 ///< Operation ended normally
#define BLE_DONE_RXTIMEOUT 0x1401 ///< Timeout of first Rx of slave operation or end of scan window
#define BLE_DONE_NOSYNC 0x1402 ///< Timeout of subsequent Rx
#define BLE_DONE_RXERR 0x1403 ///< Operation ended because of receive error (CRC or other)
#define BLE_DONE_CONNECT 0x1404 ///< CONNECT_REQ received or transmitted
#define BLE_DONE_MAXNACK 0x1405 ///< Maximum number of retransmissions exceeded
#define BLE_DONE_ENDED 0x1406 ///< Operation stopped after end trigger
#define BLE_DONE_ABORT 0x1407 ///< Operation aborted by command
#define BLE_DONE_STOPPED 0x1408 ///< Operation stopped after stop command
///@}
/// \name Operation finished with error
///@{
#define BLE_ERROR_PAR 0x1800 ///< Illegal parameter
#define BLE_ERROR_RXBUF 0x1801 ///< No available Rx buffer (Advertiser, Scanner, Initiator)
#define BLE_ERROR_NO_SETUP 0x1802 ///< Operation using Rx or Tx attemted when not in BLE mode
#define BLE_ERROR_NO_FS 0x1803 ///< Operation using Rx or Tx attemted without frequency synth configured
#define BLE_ERROR_SYNTH_PROG 0x1804 ///< Synthesizer programming failed to complete on time
#define BLE_ERROR_RXOVF 0x1805 ///< Receiver overflowed during operation
#define BLE_ERROR_TXUNF 0x1806 ///< Transmitter underflowed during operation
///@}
///@}
#endif

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,448 @@
/******************************************************************************
* Filename: common_cmd_field.h
* Revised: $ $
* Revision: $ $
*
* Description: CC26xx API for common/generic commands
*
* Copyright (C) 2015 Texas Instruments Incorporated - http://www.ti.com/
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* Neither the name of Texas Instruments Incorporated 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
* OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
* DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
* THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************/
#ifndef __COMMON_CMD_FIELD_H
#define __COMMON_CMD_FIELD_H
#include <stdint.h>
#include "mailbox.h"
#define _POSITION_command_commandNo 0
#define _TYPE_command_commandNo uint16_t
#define _SIZEOF_command 2
#define _POSITION_radioOp_commandNo 0
#define _TYPE_radioOp_commandNo uint16_t
#define _POSITION_radioOp_status 2
#define _TYPE_radioOp_status uint16_t
#define _POSITION_radioOp_pNextOp 4
#define _TYPE_radioOp_pNextOp uint8_t*
#define _POSITION_radioOp_startTime 8
#define _TYPE_radioOp_startTime ratmr_t
#define _POSITION_radioOp_startTrigger 12
#define _TYPE_radioOp_startTrigger uint8_t
#define _BITPOS_radioOp_startTrigger_triggerType 0
#define _NBITS_radioOp_startTrigger_triggerType 4
#define _BITPOS_radioOp_startTrigger_bEnaCmd 4
#define _NBITS_radioOp_startTrigger_bEnaCmd 1
#define _BITPOS_radioOp_startTrigger_triggerNo 5
#define _NBITS_radioOp_startTrigger_triggerNo 2
#define _BITPOS_radioOp_startTrigger_pastTrig 7
#define _NBITS_radioOp_startTrigger_pastTrig 1
#define _POSITION_radioOp_condition 13
#define _TYPE_radioOp_condition uint8_t
#define _BITPOS_radioOp_condition_rule 0
#define _NBITS_radioOp_condition_rule 4
#define _BITPOS_radioOp_condition_nSkip 4
#define _NBITS_radioOp_condition_nSkip 4
#define _SIZEOF_radioOp 14
#define _SIZEOF_CMD_NOP 14
#define _POSITION_CMD_RADIO_SETUP_mode 14
#define _TYPE_CMD_RADIO_SETUP_mode uint8_t
#define _POSITION_CMD_RADIO_SETUP_config 16
#define _TYPE_CMD_RADIO_SETUP_config uint16_t
#define _BITPOS_CMD_RADIO_SETUP_config_frontEndMode 0
#define _NBITS_CMD_RADIO_SETUP_config_frontEndMode 3
#define _BITPOS_CMD_RADIO_SETUP_config_biasMode 3
#define _NBITS_CMD_RADIO_SETUP_config_biasMode 1
#define _BITPOS_CMD_RADIO_SETUP_config_bNoAdi0Setup 4
#define _NBITS_CMD_RADIO_SETUP_config_bNoAdi0Setup 1
#define _BITPOS_CMD_RADIO_SETUP_config_bNoAdi0Trim 5
#define _NBITS_CMD_RADIO_SETUP_config_bNoAdi0Trim 1
#define _BITPOS_CMD_RADIO_SETUP_config_bNoAdi0Ovr 6
#define _NBITS_CMD_RADIO_SETUP_config_bNoAdi0Ovr 1
#define _BITPOS_CMD_RADIO_SETUP_config_bNoAdi1Setup 7
#define _NBITS_CMD_RADIO_SETUP_config_bNoAdi1Setup 1
#define _BITPOS_CMD_RADIO_SETUP_config_bNoAdi1Trim 8
#define _NBITS_CMD_RADIO_SETUP_config_bNoAdi1Trim 1
#define _BITPOS_CMD_RADIO_SETUP_config_bNoAdi1Ovr 9
#define _NBITS_CMD_RADIO_SETUP_config_bNoAdi1Ovr 1
#define _BITPOS_CMD_RADIO_SETUP_config_bNoFsPowerUp 10
#define _NBITS_CMD_RADIO_SETUP_config_bNoFsPowerUp 1
#define _POSITION_CMD_RADIO_SETUP_txPower 18
#define _TYPE_CMD_RADIO_SETUP_txPower uint16_t
#define _BITPOS_CMD_RADIO_SETUP_txPower_IB 0
#define _NBITS_CMD_RADIO_SETUP_txPower_IB 6
#define _BITPOS_CMD_RADIO_SETUP_txPower_GC 6
#define _NBITS_CMD_RADIO_SETUP_txPower_GC 2
#define _BITPOS_CMD_RADIO_SETUP_txPower_tempCoeff 8
#define _NBITS_CMD_RADIO_SETUP_txPower_tempCoeff 8
#define _POSITION_CMD_RADIO_SETUP_pRegOverride 20
#define _TYPE_CMD_RADIO_SETUP_pRegOverride uint32_t*
#define _SIZEOF_CMD_RADIO_SETUP 24
#define _POSITION_CMD_FS_frequency 14
#define _TYPE_CMD_FS_frequency uint16_t
#define _POSITION_CMD_FS_fractFreq 16
#define _TYPE_CMD_FS_fractFreq uint16_t
#define _POSITION_CMD_FS_synthConf 18
#define _TYPE_CMD_FS_synthConf uint8_t
#define _BITPOS_CMD_FS_synthConf_bTxMode 0
#define _NBITS_CMD_FS_synthConf_bTxMode 1
#define _BITPOS_CMD_FS_synthConf_refFreq 1
#define _NBITS_CMD_FS_synthConf_refFreq 6
#define _POSITION_CMD_FS_calibConf 19
#define _TYPE_CMD_FS_calibConf uint8_t
#define _BITPOS_CMD_FS_calibConf_bOverrideCalib 0
#define _NBITS_CMD_FS_calibConf_bOverrideCalib 1
#define _BITPOS_CMD_FS_calibConf_bSkipTdcCalib 1
#define _NBITS_CMD_FS_calibConf_bSkipTdcCalib 1
#define _BITPOS_CMD_FS_calibConf_bSkipCoarseCalib 2
#define _NBITS_CMD_FS_calibConf_bSkipCoarseCalib 1
#define _BITPOS_CMD_FS_calibConf_bSkipMidCalib 3
#define _NBITS_CMD_FS_calibConf_bSkipMidCalib 1
#define _BITPOS_CMD_FS_calibConf_coarsePrecal 4
#define _NBITS_CMD_FS_calibConf_coarsePrecal 4
#define _POSITION_CMD_FS_midPrecal 20
#define _TYPE_CMD_FS_midPrecal uint8_t
#define _POSITION_CMD_FS_ktPrecal 21
#define _TYPE_CMD_FS_ktPrecal uint8_t
#define _POSITION_CMD_FS_tdcPrecal 22
#define _TYPE_CMD_FS_tdcPrecal uint16_t
#define _SIZEOF_CMD_FS 24
#define _SIZEOF_CMD_FS_OFF 14
#define _POSITION_CMD_RX_pktConfig 14
#define _TYPE_CMD_RX_pktConfig uint16_t
#define _BITPOS_CMD_RX_pktConfig_endianness 0
#define _NBITS_CMD_RX_pktConfig_endianness 1
#define _BITPOS_CMD_RX_pktConfig_numHdrBits 1
#define _NBITS_CMD_RX_pktConfig_numHdrBits 6
#define _BITPOS_CMD_RX_pktConfig_bFsOff 7
#define _NBITS_CMD_RX_pktConfig_bFsOff 1
#define _BITPOS_CMD_RX_pktConfig_bUseCrc 8
#define _NBITS_CMD_RX_pktConfig_bUseCrc 1
#define _BITPOS_CMD_RX_pktConfig_bCrcIncSw 9
#define _NBITS_CMD_RX_pktConfig_bCrcIncSw 1
#define _BITPOS_CMD_RX_pktConfig_bCrcIncHdr 10
#define _NBITS_CMD_RX_pktConfig_bCrcIncHdr 1
#define _BITPOS_CMD_RX_pktConfig_bReportCrc 11
#define _NBITS_CMD_RX_pktConfig_bReportCrc 1
#define _BITPOS_CMD_RX_pktConfig_endType 12
#define _NBITS_CMD_RX_pktConfig_endType 1
#define _BITPOS_CMD_RX_pktConfig_bDualSw 13
#define _NBITS_CMD_RX_pktConfig_bDualSw 1
#define _POSITION_CMD_RX_syncWord 16
#define _TYPE_CMD_RX_syncWord uint32_t
#define _POSITION_CMD_RX_syncWord2 20
#define _TYPE_CMD_RX_syncWord2 uint32_t
#define _POSITION_CMD_RX_lenConfig 24
#define _TYPE_CMD_RX_lenConfig uint16_t
#define _BITPOS_CMD_RX_lenConfig_numLenBits 0
#define _NBITS_CMD_RX_lenConfig_numLenBits 4
#define _BITPOS_CMD_RX_lenConfig_lenFieldPos 4
#define _NBITS_CMD_RX_lenConfig_lenFieldPos 5
#define _BITPOS_CMD_RX_lenConfig_lenOffset 9
#define _NBITS_CMD_RX_lenConfig_lenOffset 7
#define _POSITION_CMD_RX_maxLen 26
#define _TYPE_CMD_RX_maxLen uint16_t
#define _POSITION_CMD_RX_pRecPkt 28
#define _TYPE_CMD_RX_pRecPkt uint8_t*
#define _POSITION_CMD_RX_endTime 32
#define _TYPE_CMD_RX_endTime ratmr_t
#define _POSITION_CMD_RX_endTrigger 36
#define _TYPE_CMD_RX_endTrigger uint8_t
#define _BITPOS_CMD_RX_endTrigger_triggerType 0
#define _NBITS_CMD_RX_endTrigger_triggerType 4
#define _BITPOS_CMD_RX_endTrigger_bEnaCmd 4
#define _NBITS_CMD_RX_endTrigger_bEnaCmd 1
#define _BITPOS_CMD_RX_endTrigger_triggerNo 5
#define _NBITS_CMD_RX_endTrigger_triggerNo 2
#define _BITPOS_CMD_RX_endTrigger_pastTrig 7
#define _NBITS_CMD_RX_endTrigger_pastTrig 1
#define _POSITION_CMD_RX_rssi 37
#define _TYPE_CMD_RX_rssi int8_t
#define _POSITION_CMD_RX_recLen 38
#define _TYPE_CMD_RX_recLen uint16_t
#define _POSITION_CMD_RX_timeStamp 40
#define _TYPE_CMD_RX_timeStamp ratmr_t
#define _POSITION_CMD_RX_nRxOk 44
#define _TYPE_CMD_RX_nRxOk uint16_t
#define _POSITION_CMD_RX_nRxNok 46
#define _TYPE_CMD_RX_nRxNok uint16_t
#define _POSITION_CMD_RX_nRx2Ok 48
#define _TYPE_CMD_RX_nRx2Ok uint16_t
#define _POSITION_CMD_RX_nRx2Nok 50
#define _TYPE_CMD_RX_nRx2Nok uint16_t
#define _SIZEOF_CMD_RX 52
#define _POSITION_CMD_TX_pktConfig 14
#define _TYPE_CMD_TX_pktConfig uint16_t
#define _BITPOS_CMD_TX_pktConfig_endianness 0
#define _NBITS_CMD_TX_pktConfig_endianness 1
#define _BITPOS_CMD_TX_pktConfig_numHdrBits 1
#define _NBITS_CMD_TX_pktConfig_numHdrBits 6
#define _BITPOS_CMD_TX_pktConfig_bFsOff 7
#define _NBITS_CMD_TX_pktConfig_bFsOff 1
#define _BITPOS_CMD_TX_pktConfig_bUseCrc 8
#define _NBITS_CMD_TX_pktConfig_bUseCrc 1
#define _BITPOS_CMD_TX_pktConfig_bCrcIncSw 9
#define _NBITS_CMD_TX_pktConfig_bCrcIncSw 1
#define _BITPOS_CMD_TX_pktConfig_bCrcIncHdr 10
#define _NBITS_CMD_TX_pktConfig_bCrcIncHdr 1
#define _POSITION_CMD_TX_syncWord 16
#define _TYPE_CMD_TX_syncWord uint32_t
#define _POSITION_CMD_TX_pTxPkt 20
#define _TYPE_CMD_TX_pTxPkt uint8_t*
#define _POSITION_CMD_TX_pktLen 24
#define _TYPE_CMD_TX_pktLen uint16_t
#define _SIZEOF_CMD_TX 26
#define _POSITION_CMD_RX_TEST_config 14
#define _TYPE_CMD_RX_TEST_config uint8_t
#define _BITPOS_CMD_RX_TEST_config_bEnaFifo 0
#define _NBITS_CMD_RX_TEST_config_bEnaFifo 1
#define _BITPOS_CMD_RX_TEST_config_bFsOff 1
#define _NBITS_CMD_RX_TEST_config_bFsOff 1
#define _BITPOS_CMD_RX_TEST_config_bNoSync 2
#define _NBITS_CMD_RX_TEST_config_bNoSync 1
#define _POSITION_CMD_RX_TEST_endTrigger 15
#define _TYPE_CMD_RX_TEST_endTrigger uint8_t
#define _BITPOS_CMD_RX_TEST_endTrigger_triggerType 0
#define _NBITS_CMD_RX_TEST_endTrigger_triggerType 4
#define _BITPOS_CMD_RX_TEST_endTrigger_bEnaCmd 4
#define _NBITS_CMD_RX_TEST_endTrigger_bEnaCmd 1
#define _BITPOS_CMD_RX_TEST_endTrigger_triggerNo 5
#define _NBITS_CMD_RX_TEST_endTrigger_triggerNo 2
#define _BITPOS_CMD_RX_TEST_endTrigger_pastTrig 7
#define _NBITS_CMD_RX_TEST_endTrigger_pastTrig 1
#define _POSITION_CMD_RX_TEST_syncWord 16
#define _TYPE_CMD_RX_TEST_syncWord uint32_t
#define _POSITION_CMD_RX_TEST_endTime 20
#define _TYPE_CMD_RX_TEST_endTime ratmr_t
#define _SIZEOF_CMD_RX_TEST 24
#define _POSITION_CMD_TX_TEST_config 14
#define _TYPE_CMD_TX_TEST_config uint8_t
#define _BITPOS_CMD_TX_TEST_config_bUseCw 0
#define _NBITS_CMD_TX_TEST_config_bUseCw 1
#define _BITPOS_CMD_TX_TEST_config_bFsOff 1
#define _NBITS_CMD_TX_TEST_config_bFsOff 1
#define _BITPOS_CMD_TX_TEST_config_whitenMode 2
#define _NBITS_CMD_TX_TEST_config_whitenMode 2
#define _POSITION_CMD_TX_TEST_txWord 16
#define _TYPE_CMD_TX_TEST_txWord uint16_t
#define _POSITION_CMD_TX_TEST_endTrigger 19
#define _TYPE_CMD_TX_TEST_endTrigger uint8_t
#define _BITPOS_CMD_TX_TEST_endTrigger_triggerType 0
#define _NBITS_CMD_TX_TEST_endTrigger_triggerType 4
#define _BITPOS_CMD_TX_TEST_endTrigger_bEnaCmd 4
#define _NBITS_CMD_TX_TEST_endTrigger_bEnaCmd 1
#define _BITPOS_CMD_TX_TEST_endTrigger_triggerNo 5
#define _NBITS_CMD_TX_TEST_endTrigger_triggerNo 2
#define _BITPOS_CMD_TX_TEST_endTrigger_pastTrig 7
#define _NBITS_CMD_TX_TEST_endTrigger_pastTrig 1
#define _POSITION_CMD_TX_TEST_syncWord 20
#define _TYPE_CMD_TX_TEST_syncWord uint32_t
#define _POSITION_CMD_TX_TEST_endTime 24
#define _TYPE_CMD_TX_TEST_endTime ratmr_t
#define _SIZEOF_CMD_TX_TEST 28
#define _POSITION_CMD_SYNC_STOP_RAT_rat0 16
#define _TYPE_CMD_SYNC_STOP_RAT_rat0 ratmr_t
#define _SIZEOF_CMD_SYNC_STOP_RAT 20
#define _POSITION_CMD_SYNC_START_RAT_rat0 16
#define _TYPE_CMD_SYNC_START_RAT_rat0 ratmr_t
#define _SIZEOF_CMD_SYNC_START_RAT 20
#define _POSITION_CMD_COUNT_counter 14
#define _TYPE_CMD_COUNT_counter uint16_t
#define _SIZEOF_CMD_COUNT 16
#define _POSITION_CMD_FS_POWERUP_pRegOverride 16
#define _TYPE_CMD_FS_POWERUP_pRegOverride uint32_t*
#define _SIZEOF_CMD_FS_POWERUP 20
#define _SIZEOF_CMD_FS_POWERDOWN 14
#define _POSITION_CMD_SCH_IMM_cmdrVal 16
#define _TYPE_CMD_SCH_IMM_cmdrVal uint32_t
#define _POSITION_CMD_SCH_IMM_cmdstaVal 20
#define _TYPE_CMD_SCH_IMM_cmdstaVal uint32_t
#define _SIZEOF_CMD_SCH_IMM 24
#define _POSITION_CMD_COUNT_BRANCH_counter 14
#define _TYPE_CMD_COUNT_BRANCH_counter uint16_t
#define _POSITION_CMD_COUNT_BRANCH_pNextOpIfOk 16
#define _TYPE_CMD_COUNT_BRANCH_pNextOpIfOk uint8_t*
#define _SIZEOF_CMD_COUNT_BRANCH 20
#define _POSITION_CMD_PATTERN_CHECK_patternOpt 14
#define _TYPE_CMD_PATTERN_CHECK_patternOpt uint16_t
#define _BITPOS_CMD_PATTERN_CHECK_patternOpt_operation 0
#define _NBITS_CMD_PATTERN_CHECK_patternOpt_operation 2
#define _BITPOS_CMD_PATTERN_CHECK_patternOpt_bByteRev 2
#define _NBITS_CMD_PATTERN_CHECK_patternOpt_bByteRev 1
#define _BITPOS_CMD_PATTERN_CHECK_patternOpt_bBitRev 3
#define _NBITS_CMD_PATTERN_CHECK_patternOpt_bBitRev 1
#define _BITPOS_CMD_PATTERN_CHECK_patternOpt_signExtend 4
#define _NBITS_CMD_PATTERN_CHECK_patternOpt_signExtend 5
#define _BITPOS_CMD_PATTERN_CHECK_patternOpt_bRxVal 9
#define _NBITS_CMD_PATTERN_CHECK_patternOpt_bRxVal 1
#define _POSITION_CMD_PATTERN_CHECK_pNextOpIfOk 16
#define _TYPE_CMD_PATTERN_CHECK_pNextOpIfOk uint8_t*
#define _POSITION_CMD_PATTERN_CHECK_pValue 20
#define _TYPE_CMD_PATTERN_CHECK_pValue uint8_t*
#define _POSITION_CMD_PATTERN_CHECK_mask 24
#define _TYPE_CMD_PATTERN_CHECK_mask uint32_t
#define _POSITION_CMD_PATTERN_CHECK_compareVal 28
#define _TYPE_CMD_PATTERN_CHECK_compareVal uint32_t
#define _SIZEOF_CMD_PATTERN_CHECK 32
#define _SIZEOF_CMD_ABORT 2
#define _SIZEOF_CMD_STOP 2
#define _SIZEOF_CMD_GET_RSSI 2
#define _POSITION_CMD_UPDATE_RADIO_SETUP_pRegOverride 4
#define _TYPE_CMD_UPDATE_RADIO_SETUP_pRegOverride uint32_t*
#define _SIZEOF_CMD_UPDATE_RADIO_SETUP 8
#define _POSITION_CMD_TRIGGER_triggerNo 2
#define _TYPE_CMD_TRIGGER_triggerNo uint8_t
#define _SIZEOF_CMD_TRIGGER 3
#define _POSITION_CMD_GET_FW_INFO_versionNo 2
#define _TYPE_CMD_GET_FW_INFO_versionNo uint16_t
#define _POSITION_CMD_GET_FW_INFO_startOffset 4
#define _TYPE_CMD_GET_FW_INFO_startOffset uint16_t
#define _POSITION_CMD_GET_FW_INFO_freeRamSz 6
#define _TYPE_CMD_GET_FW_INFO_freeRamSz uint16_t
#define _POSITION_CMD_GET_FW_INFO_availRatCh 8
#define _TYPE_CMD_GET_FW_INFO_availRatCh uint16_t
#define _SIZEOF_CMD_GET_FW_INFO 10
#define _SIZEOF_CMD_START_RAT 2
#define _SIZEOF_CMD_PING 2
#define _POSITION_CMD_ADD_DATA_ENTRY_pQueue 4
#define _TYPE_CMD_ADD_DATA_ENTRY_pQueue dataQueue_t*
#define _POSITION_CMD_ADD_DATA_ENTRY_pEntry 8
#define _TYPE_CMD_ADD_DATA_ENTRY_pEntry uint8_t*
#define _SIZEOF_CMD_ADD_DATA_ENTRY 12
#define _POSITION_CMD_REMOVE_DATA_ENTRY_pQueue 4
#define _TYPE_CMD_REMOVE_DATA_ENTRY_pQueue dataQueue_t*
#define _POSITION_CMD_REMOVE_DATA_ENTRY_pEntry 8
#define _TYPE_CMD_REMOVE_DATA_ENTRY_pEntry uint8_t*
#define _SIZEOF_CMD_REMOVE_DATA_ENTRY 12
#define _POSITION_CMD_FLUSH_QUEUE_pQueue 4
#define _TYPE_CMD_FLUSH_QUEUE_pQueue dataQueue_t*
#define _POSITION_CMD_FLUSH_QUEUE_pFirstEntry 8
#define _TYPE_CMD_FLUSH_QUEUE_pFirstEntry uint8_t*
#define _SIZEOF_CMD_FLUSH_QUEUE 12
#define _POSITION_CMD_CLEAR_RX_pQueue 4
#define _TYPE_CMD_CLEAR_RX_pQueue dataQueue_t*
#define _SIZEOF_CMD_CLEAR_RX 8
#define _POSITION_CMD_REMOVE_PENDING_ENTRIES_pQueue 4
#define _TYPE_CMD_REMOVE_PENDING_ENTRIES_pQueue dataQueue_t*
#define _POSITION_CMD_REMOVE_PENDING_ENTRIES_pFirstEntry 8
#define _TYPE_CMD_REMOVE_PENDING_ENTRIES_pFirstEntry uint8_t*
#define _SIZEOF_CMD_REMOVE_PENDING_ENTRIES 12
#define _POSITION_CMD_SET_RAT_CMP_ratCh 2
#define _TYPE_CMD_SET_RAT_CMP_ratCh uint8_t
#define _POSITION_CMD_SET_RAT_CMP_compareTime 4
#define _TYPE_CMD_SET_RAT_CMP_compareTime ratmr_t
#define _SIZEOF_CMD_SET_RAT_CMP 8
#define _POSITION_CMD_SET_RAT_CPT_config 2
#define _TYPE_CMD_SET_RAT_CPT_config uint16_t
#define _BITPOS_CMD_SET_RAT_CPT_config_inputSrc 3
#define _NBITS_CMD_SET_RAT_CPT_config_inputSrc 5
#define _BITPOS_CMD_SET_RAT_CPT_config_ratCh 8
#define _NBITS_CMD_SET_RAT_CPT_config_ratCh 4
#define _BITPOS_CMD_SET_RAT_CPT_config_bRepeated 12
#define _NBITS_CMD_SET_RAT_CPT_config_bRepeated 1
#define _BITPOS_CMD_SET_RAT_CPT_config_inputMode 13
#define _NBITS_CMD_SET_RAT_CPT_config_inputMode 2
#define _SIZEOF_CMD_SET_RAT_CPT 4
#define _POSITION_CMD_DISABLE_RAT_CH_ratCh 2
#define _TYPE_CMD_DISABLE_RAT_CH_ratCh uint8_t
#define _SIZEOF_CMD_DISABLE_RAT_CH 3
#define _POSITION_CMD_SET_RAT_OUTPUT_config 2
#define _TYPE_CMD_SET_RAT_OUTPUT_config uint16_t
#define _BITPOS_CMD_SET_RAT_OUTPUT_config_outputSel 2
#define _NBITS_CMD_SET_RAT_OUTPUT_config_outputSel 3
#define _BITPOS_CMD_SET_RAT_OUTPUT_config_outputMode 5
#define _NBITS_CMD_SET_RAT_OUTPUT_config_outputMode 3
#define _BITPOS_CMD_SET_RAT_OUTPUT_config_ratCh 8
#define _NBITS_CMD_SET_RAT_OUTPUT_config_ratCh 4
#define _SIZEOF_CMD_SET_RAT_OUTPUT 4
#define _POSITION_CMD_ARM_RAT_CH_ratCh 2
#define _TYPE_CMD_ARM_RAT_CH_ratCh uint8_t
#define _SIZEOF_CMD_ARM_RAT_CH 3
#define _POSITION_CMD_DISARM_RAT_CH_ratCh 2
#define _TYPE_CMD_DISARM_RAT_CH_ratCh uint8_t
#define _SIZEOF_CMD_DISARM_RAT_CH 3
#define _POSITION_CMD_SET_TX_POWER_txPower 2
#define _TYPE_CMD_SET_TX_POWER_txPower uint16_t
#define _BITPOS_CMD_SET_TX_POWER_txPower_IB 0
#define _NBITS_CMD_SET_TX_POWER_txPower_IB 6
#define _BITPOS_CMD_SET_TX_POWER_txPower_GC 6
#define _NBITS_CMD_SET_TX_POWER_txPower_GC 2
#define _BITPOS_CMD_SET_TX_POWER_txPower_tempCoeff 8
#define _NBITS_CMD_SET_TX_POWER_txPower_tempCoeff 8
#define _SIZEOF_CMD_SET_TX_POWER 4
#define _POSITION_CMD_UPDATE_FS_frequency 2
#define _TYPE_CMD_UPDATE_FS_frequency uint16_t
#define _POSITION_CMD_UPDATE_FS_fractFreq 4
#define _TYPE_CMD_UPDATE_FS_fractFreq uint16_t
#define _SIZEOF_CMD_UPDATE_FS 6
#define _POSITION_CMD_BUS_REQUEST_bSysBusNeeded 2
#define _TYPE_CMD_BUS_REQUEST_bSysBusNeeded uint8_t
#define _SIZEOF_CMD_BUS_REQUEST 3
#endif

View File

@ -0,0 +1,91 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
#ifndef __DATA_ENTRY_H
#define __DATA_ENTRY_H
#include <stdint.h>
#include "mailbox.h"
typedef struct rfc_dataEntry_s rfc_dataEntry_t;
#define _POSITION_dataEntry_pNextEntry 0
#define _TYPE_dataEntry_pNextEntry uint8_t*
#define _POSITION_dataEntry_status 4
#define _TYPE_dataEntry_status uint8_t
#define _POSITION_dataEntry_config 5
#define _TYPE_dataEntry_config uint8_t
#define _BITPOS_dataEntry_config_type 0
#define _NBITS_dataEntry_config_type 2
#define _BITPOS_dataEntry_config_lenSz 2
#define _NBITS_dataEntry_config_lenSz 2
#define _BITPOS_dataEntry_config_irqIntv 4
#define _NBITS_dataEntry_config_irqIntv 4
#define _POSITION_dataEntry_length 6
#define _TYPE_dataEntry_length uint16_t
#define _POSITION_dataEntry_data 8
#define _TYPE_dataEntry_data uint8_t
#define _POSITION_dataEntry_pData 8
#define _TYPE_dataEntry_pData uint8_t*
#define _POSITION_dataEntry_numElements 8
#define _TYPE_dataEntry_numElements uint16_t
#define _POSITION_dataEntry_pktStatus 8
#define _TYPE_dataEntry_pktStatus uint16_t
#define _BITPOS_dataEntry_pktStatus_numElements 0
#define _NBITS_dataEntry_pktStatus_numElements 13
#define _BITPOS_dataEntry_pktStatus_bEntryOpen 13
#define _NBITS_dataEntry_pktStatus_bEntryOpen 1
#define _BITPOS_dataEntry_pktStatus_bFirstCont 14
#define _NBITS_dataEntry_pktStatus_bFirstCont 1
#define _BITPOS_dataEntry_pktStatus_bLastCont 15
#define _NBITS_dataEntry_pktStatus_bLastCont 1
#define _POSITION_dataEntry_nextIndex 10
#define _TYPE_dataEntry_nextIndex uint16_t
#define _POSITION_dataEntry_rxData 12
#define _TYPE_dataEntry_rxData uint8_t
#define _LAST_POSITION_dataEntry 12
#define _LAST_TYPE_dataEntry uint8_t
struct rfc_dataEntry_s {
uint8_t* pNextEntry;
uint8_t status;
struct {
uint8_t type:2;
uint8_t lenSz:2;
uint8_t irqIntv:4;
} config;
uint16_t length;
uint8_t data;
uint8_t __dummy0;
uint16_t nextIndex;
uint8_t rxData;
};
#endif

View File

@ -0,0 +1,614 @@
/******************************************************************************
* Filename: ieee_cmd.h
* Revised: $ $
* Revision: $ $
*
* Description: CC26xx/CC13xx API for IEEE 802.15.4 commands
*
* Copyright (C) 2015 Texas Instruments Incorporated - http://www.ti.com/
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* Neither the name of Texas Instruments Incorporated 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
* OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
* DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
* THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************/
#ifndef __IEEE_CMD_H
#define __IEEE_CMD_H
#ifndef __RFC_STRUCT
#ifdef __GNUC__
#define __RFC_STRUCT __attribute__ ((aligned (4)))
#else
#define __RFC_STRUCT
#endif
#endif
//! \addtogroup rfc
//! @{
//! \addtogroup ieee_cmd
//! @{
#include <stdint.h>
#include "mailbox.h"
#include "common_cmd.h"
typedef struct __RFC_STRUCT rfc_CMD_IEEE_RX_s rfc_CMD_IEEE_RX_t;
typedef struct __RFC_STRUCT rfc_shortAddrEntry_s rfc_shortAddrEntry_t;
typedef struct __RFC_STRUCT rfc_CMD_IEEE_CSMA_s rfc_CMD_IEEE_CSMA_t;
typedef struct __RFC_STRUCT rfc_ieeeAuxSecCtrl_s rfc_ieeeAuxSecCtrl_t;
typedef struct __RFC_STRUCT rfc_ieeeRxCorrCrc_s rfc_ieeeRxCorrCrc_t;
typedef struct __RFC_STRUCT rfc_CMD_IEEE_RX_ACK_s rfc_CMD_IEEE_RX_ACK_t;
typedef struct __RFC_STRUCT rfc_CMD_IEEE_ABORT_BG_s rfc_CMD_IEEE_ABORT_BG_t;
typedef struct __RFC_STRUCT rfc_CMD_IEEE_ED_SCAN_s rfc_CMD_IEEE_ED_SCAN_t;
typedef struct __RFC_STRUCT rfc_ieeeMacHdr_s rfc_ieeeMacHdr_t;
typedef struct __RFC_STRUCT rfc_CMD_IEEE_ABORT_FG_s rfc_CMD_IEEE_ABORT_FG_t;
typedef struct __RFC_STRUCT rfc_CMD_IEEE_CCA_REQ_s rfc_CMD_IEEE_CCA_REQ_t;
typedef struct __RFC_STRUCT rfc_CMD_IEEE_SETUP_s rfc_CMD_IEEE_SETUP_t;
typedef struct __RFC_STRUCT rfc_ieeeRxOutput_s rfc_ieeeRxOutput_t;
typedef struct __RFC_STRUCT rfc_CMD_IEEE_MOD_SRC_MATCH_s rfc_CMD_IEEE_MOD_SRC_MATCH_t;
typedef struct __RFC_STRUCT rfc_CMD_IEEE_STOP_FG_s rfc_CMD_IEEE_STOP_FG_t;
typedef struct __RFC_STRUCT rfc_CMD_IEEE_TX_s rfc_CMD_IEEE_TX_t;
typedef struct __RFC_STRUCT rfc_CMD_IEEE_MOD_FILT_s rfc_CMD_IEEE_MOD_FILT_t;
typedef struct __RFC_STRUCT rfc_CMD_IEEE_MOD_CCA_s rfc_CMD_IEEE_MOD_CCA_t;
//! \addtogroup CMD_IEEE_RX
//! @{
#define CMD_IEEE_RX 0x2801
struct __RFC_STRUCT rfc_CMD_IEEE_RX_s {
uint16_t commandNo; //!< The command ID number 0x2801
uint16_t status; //!< \brief An integer telling the status of the command. This value is
//!< updated by the radio CPU during operation and may be read by the
//!< system CPU at any time.
rfc_radioOp_t *pNextOp; //!< Pointer to the next operation to run after this operation is done
ratmr_t startTime; //!< Absolute or relative start time (depending on the value of <code>startTrigger</code>)
struct {
uint8_t triggerType:4; //!< The type of trigger
uint8_t bEnaCmd:1; //!< \brief 0: No alternative trigger command<br>
//!< 1: CMD_TRIGGER can be used as an alternative trigger
uint8_t triggerNo:2; //!< The trigger number of the CMD_TRIGGER command that triggers this action
uint8_t pastTrig:1; //!< \brief 0: A trigger in the past is never triggered, or for start of commands, give an error<br>
//!< 1: A trigger in the past is triggered as soon as possible
} startTrigger; //!< Identification of the trigger that starts the operation
struct {
uint8_t rule:4; //!< Condition for running next command: Rule for how to proceed
uint8_t nSkip:4; //!< Number of skips if the rule involves skipping
} condition;
uint8_t channel; //!< \brief Channel to tune to in the start of the operation<br>
//!< 0: Use existing channel<br>
//!< 11&ndash;26: Use as IEEE 802.15.4 channel, i.e. frequency is (2405 + 5 &times; (channel - 11)) MHz<br>
//!< 60&ndash;207: Frequency is (2300 + channel) MHz<br>
//!< Others: <i>Reserved</i>
struct {
uint8_t bAutoFlushCrc:1; //!< If 1, automatically remove packets with CRC error from Rx queue
uint8_t bAutoFlushIgn:1; //!< If 1, automatically remove packets that can be ignored according to frame filtering from Rx queue
uint8_t bIncludePhyHdr:1; //!< If 1, include the received PHY header field in the stored packet; otherwise discard it
uint8_t bIncludeCrc:1; //!< If 1, include the received CRC field in the stored packet; otherwise discard it
uint8_t bAppendRssi:1; //!< If 1, append an RSSI byte to the packet in the Rx queue
uint8_t bAppendCorrCrc:1; //!< If 1, append a correlation value and CRC result byte to the packet in the Rx queue
uint8_t bAppendSrcInd:1; //!< If 1, append an index from the source matching algorithm
uint8_t bAppendTimestamp:1; //!< If 1, append a timestamp to the packet in the Rx queue
} rxConfig;
dataQueue_t* pRxQ; //!< Pointer to receive queue
rfc_ieeeRxOutput_t *pOutput; //!< Pointer to output structure (NULL: Do not store results)
struct {
uint16_t frameFiltEn:1; //!< \brief 0: Disable frame filtering<br>
//!< 1: Enable frame filtering
uint16_t frameFiltStop:1; //!< \brief 0: Receive all packets to the end<br>
//!< 1: Stop receiving frame once frame filtering has caused the frame to be rejected.
uint16_t autoAckEn:1; //!< \brief 0: Disable auto ACK<br>
//!< 1: Enable auto ACK.
uint16_t slottedAckEn:1; //!< \brief 0: Non-slotted ACK<br>
//!< 1: Slotted ACK.
uint16_t autoPendEn:1; //!< \brief 0: Auto-pend disabled<br>
//!< 1: Auto-pend enabled
uint16_t defaultPend:1; //!< The value of the pending data bit in auto ACK packets that are not subject to auto-pend
uint16_t bPendDataReqOnly:1; //!< \brief 0: Use auto-pend for any packet<br>
//!< 1: Use auto-pend for data request packets only
uint16_t bPanCoord:1; //!< \brief 0: Device is not PAN coordinator<br>
//!< 1: Device is PAN coordinator
uint16_t maxFrameVersion:2; //!< Reject frames where the frame version field in the FCF is greater than this value
uint16_t fcfReservedMask:3; //!< Value to be AND-ed with the reserved part of the FCF; frame rejected if result is non-zero
uint16_t modifyFtFilter:2; //!< \brief Treatment of MSB of frame type field before frame-type filtering:<br>
//!< 0: No modification<br>
//!< 1: Invert MSB<br>
//!< 2: Set MSB to 0<br>
//!< 3: Set MSB to 1
uint16_t bStrictLenFilter:1; //!< \brief 0: Accept acknowledgement frames of any length >= 5<br>
//!< 1: Accept only acknowledgement frames of length 5
} frameFiltOpt; //!< Frame filtering options
struct {
uint8_t bAcceptFt0Beacon:1; //!< \brief Treatment of frames with frame type 000 (beacon):<br>
//!< 0: Reject<br>
//!< 1: Accept
uint8_t bAcceptFt1Data:1; //!< \brief Treatment of frames with frame type 001 (data):<br>
//!< 0: Reject<br>
//!< 1: Accept
uint8_t bAcceptFt2Ack:1; //!< \brief Treatment of frames with frame type 010 (ACK):<br>
//!< 0: Reject, unless running ACK receive command<br>
//!< 1: Always accept
uint8_t bAcceptFt3MacCmd:1; //!< \brief Treatment of frames with frame type 011 (MAC command):<br>
//!< 0: Reject<br>
//!< 1: Accept
uint8_t bAcceptFt4Reserved:1; //!< \brief Treatment of frames with frame type 100 (reserved):<br>
//!< 0: Reject<br>
//!< 1: Accept
uint8_t bAcceptFt5Reserved:1; //!< \brief Treatment of frames with frame type 101 (reserved):<br>
//!< 0: Reject<br>
//!< 1: Accept
uint8_t bAcceptFt6Reserved:1; //!< \brief Treatment of frames with frame type 110 (reserved):<br>
//!< 0: Reject<br>
//!< 1: Accept
uint8_t bAcceptFt7Reserved:1; //!< \brief Treatment of frames with frame type 111 (reserved):<br>
//!< 0: Reject<br>
//!< 1: Accept
} frameTypes; //!< Frame types to receive in frame filtering
struct {
uint8_t ccaEnEnergy:1; //!< Enable energy scan as CCA source
uint8_t ccaEnCorr:1; //!< Enable correlator based carrier sense as CCA source
uint8_t ccaEnSync:1; //!< Enable sync found based carrier sense as CCA source
uint8_t ccaCorrOp:1; //!< \brief Operator to use between energy based and correlator based CCA<br>
//!< 0: Report busy channel if either ccaEnergy or ccaCorr are busy<br>
//!< 1: Report busy channel if both ccaEnergy and ccaCorr are busy
uint8_t ccaSyncOp:1; //!< \brief Operator to use between sync found based CCA and the others<br>
//!< 0: Always report busy channel if ccaSync is busy<br>
//!< 1: Always report idle channel if ccaSync is idle
uint8_t ccaCorrThr:2; //!< Threshold for number of correlation peaks in correlator based carrier sense
} ccaOpt; //!< CCA options
int8_t ccaRssiThr; //!< RSSI threshold for CCA
uint8_t __dummy0;
uint8_t numExtEntries; //!< Number of extended address entries
uint8_t numShortEntries; //!< Number of short address entries
uint32_t* pExtEntryList; //!< Pointer to list of extended address entries
rfc_shortAddrEntry_t *pShortEntryList;//!< Pointer to list of short address entries
uint64_t localExtAddr; //!< The extended address of the local device
uint16_t localShortAddr; //!< The short address of the local device
uint16_t localPanID; //!< The PAN ID of the local device
uint16_t __dummy1;
uint8_t __dummy2;
struct {
uint8_t triggerType:4; //!< The type of trigger
uint8_t bEnaCmd:1; //!< \brief 0: No alternative trigger command<br>
//!< 1: CMD_TRIGGER can be used as an alternative trigger
uint8_t triggerNo:2; //!< The trigger number of the CMD_TRIGGER command that triggers this action
uint8_t pastTrig:1; //!< \brief 0: A trigger in the past is never triggered, or for start of commands, give an error<br>
//!< 1: A trigger in the past is triggered as soon as possible
} endTrigger; //!< Trigger that causes the device to end the Rx operation
ratmr_t endTime; //!< \brief Time used together with <code>endTrigger</code> that causes the device to end the Rx
//!< operation
};
//! @}
//! \addtogroup CMD_IEEE_ED_SCAN
//! @{
#define CMD_IEEE_ED_SCAN 0x2802
struct __RFC_STRUCT rfc_CMD_IEEE_ED_SCAN_s {
uint16_t commandNo; //!< The command ID number 0x2802
uint16_t status; //!< \brief An integer telling the status of the command. This value is
//!< updated by the radio CPU during operation and may be read by the
//!< system CPU at any time.
rfc_radioOp_t *pNextOp; //!< Pointer to the next operation to run after this operation is done
ratmr_t startTime; //!< Absolute or relative start time (depending on the value of <code>startTrigger</code>)
struct {
uint8_t triggerType:4; //!< The type of trigger
uint8_t bEnaCmd:1; //!< \brief 0: No alternative trigger command<br>
//!< 1: CMD_TRIGGER can be used as an alternative trigger
uint8_t triggerNo:2; //!< The trigger number of the CMD_TRIGGER command that triggers this action
uint8_t pastTrig:1; //!< \brief 0: A trigger in the past is never triggered, or for start of commands, give an error<br>
//!< 1: A trigger in the past is triggered as soon as possible
} startTrigger; //!< Identification of the trigger that starts the operation
struct {
uint8_t rule:4; //!< Condition for running next command: Rule for how to proceed
uint8_t nSkip:4; //!< Number of skips if the rule involves skipping
} condition;
uint8_t channel; //!< \brief Channel to tune to in the start of the operation<br>
//!< 0: Use existing channel<br>
//!< 11&ndash;26: Use as IEEE 802.15.4 channel, i.e. frequency is (2405 + 5 &times; (channel - 11)) MHz<br>
//!< 60&ndash;207: Frequency is (2300 + channel) MHz<br>
//!< Others: <i>Reserved</i>
struct {
uint8_t ccaEnEnergy:1; //!< Enable energy scan as CCA source
uint8_t ccaEnCorr:1; //!< Enable correlator based carrier sense as CCA source
uint8_t ccaEnSync:1; //!< Enable sync found based carrier sense as CCA source
uint8_t ccaCorrOp:1; //!< \brief Operator to use between energy based and correlator based CCA<br>
//!< 0: Report busy channel if either ccaEnergy or ccaCorr are busy<br>
//!< 1: Report busy channel if both ccaEnergy and ccaCorr are busy
uint8_t ccaSyncOp:1; //!< \brief Operator to use between sync found based CCA and the others<br>
//!< 0: Always report busy channel if ccaSync is busy<br>
//!< 1: Always report idle channel if ccaSync is idle
uint8_t ccaCorrThr:2; //!< Threshold for number of correlation peaks in correlator based carrier sense
} ccaOpt; //!< CCA options
int8_t ccaRssiThr; //!< RSSI threshold for CCA
uint8_t __dummy0;
int8_t maxRssi; //!< The maximum RSSI recorded during the ED scan
struct {
uint8_t triggerType:4; //!< The type of trigger
uint8_t bEnaCmd:1; //!< \brief 0: No alternative trigger command<br>
//!< 1: CMD_TRIGGER can be used as an alternative trigger
uint8_t triggerNo:2; //!< The trigger number of the CMD_TRIGGER command that triggers this action
uint8_t pastTrig:1; //!< \brief 0: A trigger in the past is never triggered, or for start of commands, give an error<br>
//!< 1: A trigger in the past is triggered as soon as possible
} endTrigger; //!< Trigger that causes the device to end the Rx operation
ratmr_t endTime; //!< \brief Time used together with <code>endTrigger</code> that causes the device to end the Rx
//!< operation
};
//! @}
//! \addtogroup CMD_IEEE_TX
//! @{
#define CMD_IEEE_TX 0x2C01
struct __RFC_STRUCT rfc_CMD_IEEE_TX_s {
uint16_t commandNo; //!< The command ID number 0x2C01
uint16_t status; //!< \brief An integer telling the status of the command. This value is
//!< updated by the radio CPU during operation and may be read by the
//!< system CPU at any time.
rfc_radioOp_t *pNextOp; //!< Pointer to the next operation to run after this operation is done
ratmr_t startTime; //!< Absolute or relative start time (depending on the value of <code>startTrigger</code>)
struct {
uint8_t triggerType:4; //!< The type of trigger
uint8_t bEnaCmd:1; //!< \brief 0: No alternative trigger command<br>
//!< 1: CMD_TRIGGER can be used as an alternative trigger
uint8_t triggerNo:2; //!< The trigger number of the CMD_TRIGGER command that triggers this action
uint8_t pastTrig:1; //!< \brief 0: A trigger in the past is never triggered, or for start of commands, give an error<br>
//!< 1: A trigger in the past is triggered as soon as possible
} startTrigger; //!< Identification of the trigger that starts the operation
struct {
uint8_t rule:4; //!< Condition for running next command: Rule for how to proceed
uint8_t nSkip:4; //!< Number of skips if the rule involves skipping
} condition;
struct {
uint8_t bIncludePhyHdr:1; //!< \brief 0: Find PHY header automatically<br>
//!< 1: Insert PHY header from the buffer
uint8_t bIncludeCrc:1; //!< \brief 0: Append automatically calculated CRC<br>
//!< 1: Insert FCS (CRC) from the buffer
uint8_t :1;
uint8_t payloadLenMsb:5; //!< \brief Most significant bits of payload length. Should only be non-zero to create long
//!< non-standard packets for test purposes
} txOpt;
uint8_t payloadLen; //!< Number of bytes in the payload
uint8_t* pPayload; //!< Pointer to payload buffer of size <code>payloadLen</code>
ratmr_t timeStamp; //!< Time stamp of transmitted frame
};
//! @}
//! \addtogroup CMD_IEEE_CSMA
//! @{
#define CMD_IEEE_CSMA 0x2C02
struct __RFC_STRUCT rfc_CMD_IEEE_CSMA_s {
uint16_t commandNo; //!< The command ID number 0x2C02
uint16_t status; //!< \brief An integer telling the status of the command. This value is
//!< updated by the radio CPU during operation and may be read by the
//!< system CPU at any time.
rfc_radioOp_t *pNextOp; //!< Pointer to the next operation to run after this operation is done
ratmr_t startTime; //!< Absolute or relative start time (depending on the value of <code>startTrigger</code>)
struct {
uint8_t triggerType:4; //!< The type of trigger
uint8_t bEnaCmd:1; //!< \brief 0: No alternative trigger command<br>
//!< 1: CMD_TRIGGER can be used as an alternative trigger
uint8_t triggerNo:2; //!< The trigger number of the CMD_TRIGGER command that triggers this action
uint8_t pastTrig:1; //!< \brief 0: A trigger in the past is never triggered, or for start of commands, give an error<br>
//!< 1: A trigger in the past is triggered as soon as possible
} startTrigger; //!< Identification of the trigger that starts the operation
struct {
uint8_t rule:4; //!< Condition for running next command: Rule for how to proceed
uint8_t nSkip:4; //!< Number of skips if the rule involves skipping
} condition;
uint16_t randomState; //!< The state of the pseudo-random generator
uint8_t macMaxBE; //!< The IEEE 802.15.4 MAC parameter <i>macMaxBE</i>
uint8_t macMaxCSMABackoffs; //!< The IEEE 802.15.4 MAC parameter <i>macMaxCSMABackoffs</i>
struct {
uint8_t initCW:5; //!< The initialization value for the CW parameter
uint8_t bSlotted:1; //!< \brief 0: non-slotted CSMA<br>
//!< 1: slotted CSMA
uint8_t rxOffMode:2; //!< \brief 0: RX stays on during CSMA backoffs<br>
//!< 1: The CSMA-CA algorithm will suspend the receiver if no frame is being received<br>
//!< 2: The CSMA-CA algorithm will suspend the receiver if no frame is being received,
//!< or after finishing it (including auto ACK) otherwise<br>
//!< 3: The CSMA-CA algorithm will suspend the receiver immediately during back-offs
} csmaConfig;
uint8_t NB; //!< The NB parameter from the IEEE 802.15.4 CSMA-CA algorithm
uint8_t BE; //!< The BE parameter from the IEEE 802.15.4 CSMA-CA algorithm
uint8_t remainingPeriods; //!< The number of remaining periods from a paused backoff countdown
int8_t lastRssi; //!< RSSI measured at the last CCA operation
struct {
uint8_t triggerType:4; //!< The type of trigger
uint8_t bEnaCmd:1; //!< \brief 0: No alternative trigger command<br>
//!< 1: CMD_TRIGGER can be used as an alternative trigger
uint8_t triggerNo:2; //!< The trigger number of the CMD_TRIGGER command that triggers this action
uint8_t pastTrig:1; //!< \brief 0: A trigger in the past is never triggered, or for start of commands, give an error<br>
//!< 1: A trigger in the past is triggered as soon as possible
} endTrigger; //!< Trigger that causes the device to end the CSMA-CA operation
ratmr_t lastTimeStamp; //!< Time of the last CCA operation
ratmr_t endTime; //!< \brief Time used together with <code>endTrigger</code> that causes the device to end the
//!< CSMA-CA operation
};
//! @}
//! \addtogroup CMD_IEEE_RX_ACK
//! @{
#define CMD_IEEE_RX_ACK 0x2C03
struct __RFC_STRUCT rfc_CMD_IEEE_RX_ACK_s {
uint16_t commandNo; //!< The command ID number 0x2C03
uint16_t status; //!< \brief An integer telling the status of the command. This value is
//!< updated by the radio CPU during operation and may be read by the
//!< system CPU at any time.
rfc_radioOp_t *pNextOp; //!< Pointer to the next operation to run after this operation is done
ratmr_t startTime; //!< Absolute or relative start time (depending on the value of <code>startTrigger</code>)
struct {
uint8_t triggerType:4; //!< The type of trigger
uint8_t bEnaCmd:1; //!< \brief 0: No alternative trigger command<br>
//!< 1: CMD_TRIGGER can be used as an alternative trigger
uint8_t triggerNo:2; //!< The trigger number of the CMD_TRIGGER command that triggers this action
uint8_t pastTrig:1; //!< \brief 0: A trigger in the past is never triggered, or for start of commands, give an error<br>
//!< 1: A trigger in the past is triggered as soon as possible
} startTrigger; //!< Identification of the trigger that starts the operation
struct {
uint8_t rule:4; //!< Condition for running next command: Rule for how to proceed
uint8_t nSkip:4; //!< Number of skips if the rule involves skipping
} condition;
uint8_t seqNo; //!< Sequence number to expect
struct {
uint8_t triggerType:4; //!< The type of trigger
uint8_t bEnaCmd:1; //!< \brief 0: No alternative trigger command<br>
//!< 1: CMD_TRIGGER can be used as an alternative trigger
uint8_t triggerNo:2; //!< The trigger number of the CMD_TRIGGER command that triggers this action
uint8_t pastTrig:1; //!< \brief 0: A trigger in the past is never triggered, or for start of commands, give an error<br>
//!< 1: A trigger in the past is triggered as soon as possible
} endTrigger; //!< Trigger that causes the device to give up acknowledgement reception
ratmr_t endTime; //!< \brief Time used together with <code>endTrigger</code> that causes the device to give up
//!< acknowledgement reception
};
//! @}
//! \addtogroup CMD_IEEE_ABORT_BG
//! @{
#define CMD_IEEE_ABORT_BG 0x2C04
struct __RFC_STRUCT rfc_CMD_IEEE_ABORT_BG_s {
uint16_t commandNo; //!< The command ID number 0x2C04
uint16_t status; //!< \brief An integer telling the status of the command. This value is
//!< updated by the radio CPU during operation and may be read by the
//!< system CPU at any time.
rfc_radioOp_t *pNextOp; //!< Pointer to the next operation to run after this operation is done
ratmr_t startTime; //!< Absolute or relative start time (depending on the value of <code>startTrigger</code>)
struct {
uint8_t triggerType:4; //!< The type of trigger
uint8_t bEnaCmd:1; //!< \brief 0: No alternative trigger command<br>
//!< 1: CMD_TRIGGER can be used as an alternative trigger
uint8_t triggerNo:2; //!< The trigger number of the CMD_TRIGGER command that triggers this action
uint8_t pastTrig:1; //!< \brief 0: A trigger in the past is never triggered, or for start of commands, give an error<br>
//!< 1: A trigger in the past is triggered as soon as possible
} startTrigger; //!< Identification of the trigger that starts the operation
struct {
uint8_t rule:4; //!< Condition for running next command: Rule for how to proceed
uint8_t nSkip:4; //!< Number of skips if the rule involves skipping
} condition;
};
//! @}
//! \addtogroup CMD_IEEE_MOD_CCA
//! @{
#define CMD_IEEE_MOD_CCA 0x2001
struct __RFC_STRUCT rfc_CMD_IEEE_MOD_CCA_s {
uint16_t commandNo; //!< The command ID number 0x2001
struct {
uint8_t ccaEnEnergy:1; //!< Enable energy scan as CCA source
uint8_t ccaEnCorr:1; //!< Enable correlator based carrier sense as CCA source
uint8_t ccaEnSync:1; //!< Enable sync found based carrier sense as CCA source
uint8_t ccaCorrOp:1; //!< \brief Operator to use between energy based and correlator based CCA<br>
//!< 0: Report busy channel if either ccaEnergy or ccaCorr are busy<br>
//!< 1: Report busy channel if both ccaEnergy and ccaCorr are busy
uint8_t ccaSyncOp:1; //!< \brief Operator to use between sync found based CCA and the others<br>
//!< 0: Always report busy channel if ccaSync is busy<br>
//!< 1: Always report idle channel if ccaSync is idle
uint8_t ccaCorrThr:2; //!< Threshold for number of correlation peaks in correlator based carrier sense
} newCcaOpt; //!< New value of <code>ccaOpt</code> for the running background level operation
int8_t newCcaRssiThr; //!< New value of <code>ccaRssiThr</code> for the running background level operation
};
//! @}
//! \addtogroup CMD_IEEE_MOD_FILT
//! @{
#define CMD_IEEE_MOD_FILT 0x2002
struct __RFC_STRUCT rfc_CMD_IEEE_MOD_FILT_s {
uint16_t commandNo; //!< The command ID number 0x2002
struct {
uint16_t frameFiltEn:1; //!< \brief 0: Disable frame filtering<br>
//!< 1: Enable frame filtering
uint16_t frameFiltStop:1; //!< \brief 0: Receive all packets to the end<br>
//!< 1: Stop receiving frame once frame filtering has caused the frame to be rejected.
uint16_t autoAckEn:1; //!< \brief 0: Disable auto ACK<br>
//!< 1: Enable auto ACK.
uint16_t slottedAckEn:1; //!< \brief 0: Non-slotted ACK<br>
//!< 1: Slotted ACK.
uint16_t autoPendEn:1; //!< \brief 0: Auto-pend disabled<br>
//!< 1: Auto-pend enabled
uint16_t defaultPend:1; //!< The value of the pending data bit in auto ACK packets that are not subject to auto-pend
uint16_t bPendDataReqOnly:1; //!< \brief 0: Use auto-pend for any packet<br>
//!< 1: Use auto-pend for data request packets only
uint16_t bPanCoord:1; //!< \brief 0: Device is not PAN coordinator<br>
//!< 1: Device is PAN coordinator
uint16_t maxFrameVersion:2; //!< Reject frames where the frame version field in the FCF is greater than this value
uint16_t fcfReservedMask:3; //!< Value to be AND-ed with the reserved part of the FCF; frame rejected if result is non-zero
uint16_t modifyFtFilter:2; //!< \brief Treatment of MSB of frame type field before frame-type filtering:<br>
//!< 0: No modification<br>
//!< 1: Invert MSB<br>
//!< 2: Set MSB to 0<br>
//!< 3: Set MSB to 1
uint16_t bStrictLenFilter:1; //!< \brief 0: Accept acknowledgement frames of any length >= 5<br>
//!< 1: Accept only acknowledgement frames of length 5
} newFrameFiltOpt; //!< New value of <code>frameFiltOpt</code> for the running background level operation
struct {
uint8_t bAcceptFt0Beacon:1; //!< \brief Treatment of frames with frame type 000 (beacon):<br>
//!< 0: Reject<br>
//!< 1: Accept
uint8_t bAcceptFt1Data:1; //!< \brief Treatment of frames with frame type 001 (data):<br>
//!< 0: Reject<br>
//!< 1: Accept
uint8_t bAcceptFt2Ack:1; //!< \brief Treatment of frames with frame type 010 (ACK):<br>
//!< 0: Reject, unless running ACK receive command<br>
//!< 1: Always accept
uint8_t bAcceptFt3MacCmd:1; //!< \brief Treatment of frames with frame type 011 (MAC command):<br>
//!< 0: Reject<br>
//!< 1: Accept
uint8_t bAcceptFt4Reserved:1; //!< \brief Treatment of frames with frame type 100 (reserved):<br>
//!< 0: Reject<br>
//!< 1: Accept
uint8_t bAcceptFt5Reserved:1; //!< \brief Treatment of frames with frame type 101 (reserved):<br>
//!< 0: Reject<br>
//!< 1: Accept
uint8_t bAcceptFt6Reserved:1; //!< \brief Treatment of frames with frame type 110 (reserved):<br>
//!< 0: Reject<br>
//!< 1: Accept
uint8_t bAcceptFt7Reserved:1; //!< \brief Treatment of frames with frame type 111 (reserved):<br>
//!< 0: Reject<br>
//!< 1: Accept
} newFrameTypes; //!< New value of <code>frameTypes</code> for the running background level operation
};
//! @}
//! \addtogroup CMD_IEEE_MOD_SRC_MATCH
//! @{
#define CMD_IEEE_MOD_SRC_MATCH 0x2003
struct __RFC_STRUCT rfc_CMD_IEEE_MOD_SRC_MATCH_s {
uint16_t commandNo; //!< The command ID number 0x2003
struct {
uint8_t bEnable:1; //!< \brief 0: Disable entry<br>
//!< 1: Enable entry
uint8_t srcPend:1; //!< New value of the pending bit for the entry
uint8_t entryType:1; //!< \brief 0: Extended address<br>
//!< 1: Short address
} options;
uint8_t entryNo; //!< Index of entry to enable or disable
};
//! @}
//! \addtogroup CMD_IEEE_ABORT_FG
//! @{
#define CMD_IEEE_ABORT_FG 0x2401
struct __RFC_STRUCT rfc_CMD_IEEE_ABORT_FG_s {
uint16_t commandNo; //!< The command ID number 0x2401
};
//! @}
//! \addtogroup CMD_IEEE_STOP_FG
//! @{
#define CMD_IEEE_STOP_FG 0x2402
struct __RFC_STRUCT rfc_CMD_IEEE_STOP_FG_s {
uint16_t commandNo; //!< The command ID number 0x2402
};
//! @}
//! \addtogroup CMD_IEEE_CCA_REQ
//! @{
#define CMD_IEEE_CCA_REQ 0x2403
struct __RFC_STRUCT rfc_CMD_IEEE_CCA_REQ_s {
uint16_t commandNo; //!< The command ID number 0x2403
int8_t currentRssi; //!< The RSSI currently observed on the channel
int8_t maxRssi; //!< The maximum RSSI observed on the channel since Rx was started
struct {
uint8_t ccaState:2; //!< \brief Value of the current CCA state<br>
//!< 0: Idle<br>
//!< 1: Busy<br>
//!< 2: Invalid
uint8_t ccaEnergy:2; //!< \brief Value of the current energy detect CCA state<br>
//!< 0: Idle<br>
//!< 1: Busy<br>
//!< 2: Invalid
uint8_t ccaCorr:2; //!< \brief Value of the current correlator based carrier sense CCA state<br>
//!< 0: Idle<br>
//!< 1: Busy<br>
//!< 2: Invalid
uint8_t ccaSync:1; //!< \brief Value of the current sync found based carrier sense CCA state<br>
//!< 0: Idle<br>
//!< 1: Busy
} ccaInfo;
};
//! @}
//! \addtogroup ieeeRxOutput
//! @{
//! Output structure for CMD_IEEE_RX
struct __RFC_STRUCT rfc_ieeeRxOutput_s {
uint8_t nTxAck; //!< Total number of transmitted ACK frames
uint8_t nRxBeacon; //!< Number of received beacon frames
uint8_t nRxData; //!< Number of received data frames
uint8_t nRxAck; //!< Number of received acknowledgement frames
uint8_t nRxMacCmd; //!< Number of received MAC command frames
uint8_t nRxReserved; //!< Number of received frames with reserved frame type
uint8_t nRxNok; //!< Number of received frames with CRC error
uint8_t nRxIgnored; //!< Number of frames received that are to be ignored
uint8_t nRxBufFull; //!< Number of received frames discarded because the Rx buffer was full
int8_t lastRssi; //!< RSSI of last received frame
int8_t maxRssi; //!< Highest RSSI observed in the operation
uint8_t __dummy0;
ratmr_t beaconTimeStamp; //!< Time stamp of last received beacon frame
};
//! @}
//! \addtogroup shortAddrEntry
//! @{
//! Structure for short address entries
struct __RFC_STRUCT rfc_shortAddrEntry_s {
uint16_t shortAddr; //!< Short address
uint16_t panId; //!< PAN ID
};
//! @}
//! \addtogroup ieeeRxCorrCrc
//! @{
//! Receive status byte that may be appended to message in receive buffer
struct __RFC_STRUCT rfc_ieeeRxCorrCrc_s {
struct {
uint8_t corr:6; //!< The correlation value
uint8_t bIgnore:1; //!< 1 if the packet should be rejected by frame filtering, 0 otherwise
uint8_t bCrcErr:1; //!< 1 if the packet was received with CRC error, 0 otherwise
} status;
};
//! @}
//! @}
//! @}
#endif

View File

@ -0,0 +1,403 @@
/******************************************************************************
* Filename: ieee_cmd_field.h
* Revised: $ $
* Revision: $ $
*
* Description: CC26xx/CC13xx API for IEEE 802.15.4 commands
*
* Copyright (C) 2015 Texas Instruments Incorporated - http://www.ti.com/
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* Neither the name of Texas Instruments Incorporated 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
* OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
* DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
* THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************/
#ifndef __IEEE_CMD_FIELD_H
#define __IEEE_CMD_FIELD_H
#include <stdint.h>
#include "mailbox.h"
#include "common_cmd.h"
#define _POSITION_CMD_IEEE_RX_channel 14
#define _TYPE_CMD_IEEE_RX_channel uint8_t
#define _POSITION_CMD_IEEE_RX_rxConfig 15
#define _TYPE_CMD_IEEE_RX_rxConfig uint8_t
#define _BITPOS_CMD_IEEE_RX_rxConfig_bAutoFlushCrc 0
#define _NBITS_CMD_IEEE_RX_rxConfig_bAutoFlushCrc 1
#define _BITPOS_CMD_IEEE_RX_rxConfig_bAutoFlushIgn 1
#define _NBITS_CMD_IEEE_RX_rxConfig_bAutoFlushIgn 1
#define _BITPOS_CMD_IEEE_RX_rxConfig_bIncludePhyHdr 2
#define _NBITS_CMD_IEEE_RX_rxConfig_bIncludePhyHdr 1
#define _BITPOS_CMD_IEEE_RX_rxConfig_bIncludeCrc 3
#define _NBITS_CMD_IEEE_RX_rxConfig_bIncludeCrc 1
#define _BITPOS_CMD_IEEE_RX_rxConfig_bAppendRssi 4
#define _NBITS_CMD_IEEE_RX_rxConfig_bAppendRssi 1
#define _BITPOS_CMD_IEEE_RX_rxConfig_bAppendCorrCrc 5
#define _NBITS_CMD_IEEE_RX_rxConfig_bAppendCorrCrc 1
#define _BITPOS_CMD_IEEE_RX_rxConfig_bAppendSrcInd 6
#define _NBITS_CMD_IEEE_RX_rxConfig_bAppendSrcInd 1
#define _BITPOS_CMD_IEEE_RX_rxConfig_bAppendTimestamp 7
#define _NBITS_CMD_IEEE_RX_rxConfig_bAppendTimestamp 1
#define _POSITION_CMD_IEEE_RX_pRxQ 16
#define _TYPE_CMD_IEEE_RX_pRxQ dataQueue_t*
#define _POSITION_CMD_IEEE_RX_pOutput 20
#define _TYPE_CMD_IEEE_RX_pOutput uint8_t*
#define _POSITION_CMD_IEEE_RX_frameFiltOpt 24
#define _TYPE_CMD_IEEE_RX_frameFiltOpt uint16_t
#define _BITPOS_CMD_IEEE_RX_frameFiltOpt_frameFiltEn 0
#define _NBITS_CMD_IEEE_RX_frameFiltOpt_frameFiltEn 1
#define _BITPOS_CMD_IEEE_RX_frameFiltOpt_frameFiltStop 1
#define _NBITS_CMD_IEEE_RX_frameFiltOpt_frameFiltStop 1
#define _BITPOS_CMD_IEEE_RX_frameFiltOpt_autoAckEn 2
#define _NBITS_CMD_IEEE_RX_frameFiltOpt_autoAckEn 1
#define _BITPOS_CMD_IEEE_RX_frameFiltOpt_slottedAckEn 3
#define _NBITS_CMD_IEEE_RX_frameFiltOpt_slottedAckEn 1
#define _BITPOS_CMD_IEEE_RX_frameFiltOpt_autoPendEn 4
#define _NBITS_CMD_IEEE_RX_frameFiltOpt_autoPendEn 1
#define _BITPOS_CMD_IEEE_RX_frameFiltOpt_defaultPend 5
#define _NBITS_CMD_IEEE_RX_frameFiltOpt_defaultPend 1
#define _BITPOS_CMD_IEEE_RX_frameFiltOpt_bPendDataReqOnly 6
#define _NBITS_CMD_IEEE_RX_frameFiltOpt_bPendDataReqOnly 1
#define _BITPOS_CMD_IEEE_RX_frameFiltOpt_bPanCoord 7
#define _NBITS_CMD_IEEE_RX_frameFiltOpt_bPanCoord 1
#define _BITPOS_CMD_IEEE_RX_frameFiltOpt_maxFrameVersion 8
#define _NBITS_CMD_IEEE_RX_frameFiltOpt_maxFrameVersion 2
#define _BITPOS_CMD_IEEE_RX_frameFiltOpt_fcfReservedMask 10
#define _NBITS_CMD_IEEE_RX_frameFiltOpt_fcfReservedMask 3
#define _BITPOS_CMD_IEEE_RX_frameFiltOpt_modifyFtFilter 13
#define _NBITS_CMD_IEEE_RX_frameFiltOpt_modifyFtFilter 2
#define _BITPOS_CMD_IEEE_RX_frameFiltOpt_bStrictLenFilter 15
#define _NBITS_CMD_IEEE_RX_frameFiltOpt_bStrictLenFilter 1
#define _POSITION_CMD_IEEE_RX_frameTypes 26
#define _TYPE_CMD_IEEE_RX_frameTypes uint8_t
#define _BITPOS_CMD_IEEE_RX_frameTypes_bAcceptFt0Beacon 0
#define _NBITS_CMD_IEEE_RX_frameTypes_bAcceptFt0Beacon 1
#define _BITPOS_CMD_IEEE_RX_frameTypes_bAcceptFt1Data 1
#define _NBITS_CMD_IEEE_RX_frameTypes_bAcceptFt1Data 1
#define _BITPOS_CMD_IEEE_RX_frameTypes_bAcceptFt2Ack 2
#define _NBITS_CMD_IEEE_RX_frameTypes_bAcceptFt2Ack 1
#define _BITPOS_CMD_IEEE_RX_frameTypes_bAcceptFt3MacCmd 3
#define _NBITS_CMD_IEEE_RX_frameTypes_bAcceptFt3MacCmd 1
#define _BITPOS_CMD_IEEE_RX_frameTypes_bAcceptFt4Reserved 4
#define _NBITS_CMD_IEEE_RX_frameTypes_bAcceptFt4Reserved 1
#define _BITPOS_CMD_IEEE_RX_frameTypes_bAcceptFt5Reserved 5
#define _NBITS_CMD_IEEE_RX_frameTypes_bAcceptFt5Reserved 1
#define _BITPOS_CMD_IEEE_RX_frameTypes_bAcceptFt6Reserved 6
#define _NBITS_CMD_IEEE_RX_frameTypes_bAcceptFt6Reserved 1
#define _BITPOS_CMD_IEEE_RX_frameTypes_bAcceptFt7Reserved 7
#define _NBITS_CMD_IEEE_RX_frameTypes_bAcceptFt7Reserved 1
#define _POSITION_CMD_IEEE_RX_ccaOpt 27
#define _TYPE_CMD_IEEE_RX_ccaOpt uint8_t
#define _BITPOS_CMD_IEEE_RX_ccaOpt_ccaEnEnergy 0
#define _NBITS_CMD_IEEE_RX_ccaOpt_ccaEnEnergy 1
#define _BITPOS_CMD_IEEE_RX_ccaOpt_ccaEnCorr 1
#define _NBITS_CMD_IEEE_RX_ccaOpt_ccaEnCorr 1
#define _BITPOS_CMD_IEEE_RX_ccaOpt_ccaEnSync 2
#define _NBITS_CMD_IEEE_RX_ccaOpt_ccaEnSync 1
#define _BITPOS_CMD_IEEE_RX_ccaOpt_ccaCorrOp 3
#define _NBITS_CMD_IEEE_RX_ccaOpt_ccaCorrOp 1
#define _BITPOS_CMD_IEEE_RX_ccaOpt_ccaSyncOp 4
#define _NBITS_CMD_IEEE_RX_ccaOpt_ccaSyncOp 1
#define _BITPOS_CMD_IEEE_RX_ccaOpt_ccaCorrThr 5
#define _NBITS_CMD_IEEE_RX_ccaOpt_ccaCorrThr 2
#define _POSITION_CMD_IEEE_RX_ccaRssiThr 28
#define _TYPE_CMD_IEEE_RX_ccaRssiThr int8_t
#define _POSITION_CMD_IEEE_RX_numExtEntries 30
#define _TYPE_CMD_IEEE_RX_numExtEntries uint8_t
#define _POSITION_CMD_IEEE_RX_numShortEntries 31
#define _TYPE_CMD_IEEE_RX_numShortEntries uint8_t
#define _POSITION_CMD_IEEE_RX_pExtEntryList 32
#define _TYPE_CMD_IEEE_RX_pExtEntryList uint32_t*
#define _POSITION_CMD_IEEE_RX_pShortEntryList 36
#define _TYPE_CMD_IEEE_RX_pShortEntryList uint32_t*
#define _POSITION_CMD_IEEE_RX_localExtAddr 40
#define _TYPE_CMD_IEEE_RX_localExtAddr uint64_t
#define _POSITION_CMD_IEEE_RX_localShortAddr 48
#define _TYPE_CMD_IEEE_RX_localShortAddr uint16_t
#define _POSITION_CMD_IEEE_RX_localPanID 50
#define _TYPE_CMD_IEEE_RX_localPanID uint16_t
#define _POSITION_CMD_IEEE_RX_endTrigger 55
#define _TYPE_CMD_IEEE_RX_endTrigger uint8_t
#define _BITPOS_CMD_IEEE_RX_endTrigger_triggerType 0
#define _NBITS_CMD_IEEE_RX_endTrigger_triggerType 4
#define _BITPOS_CMD_IEEE_RX_endTrigger_bEnaCmd 4
#define _NBITS_CMD_IEEE_RX_endTrigger_bEnaCmd 1
#define _BITPOS_CMD_IEEE_RX_endTrigger_triggerNo 5
#define _NBITS_CMD_IEEE_RX_endTrigger_triggerNo 2
#define _BITPOS_CMD_IEEE_RX_endTrigger_pastTrig 7
#define _NBITS_CMD_IEEE_RX_endTrigger_pastTrig 1
#define _POSITION_CMD_IEEE_RX_endTime 56
#define _TYPE_CMD_IEEE_RX_endTime ratmr_t
#define _SIZEOF_CMD_IEEE_RX 60
#define _POSITION_CMD_IEEE_ED_SCAN_channel 14
#define _TYPE_CMD_IEEE_ED_SCAN_channel uint8_t
#define _POSITION_CMD_IEEE_ED_SCAN_ccaOpt 15
#define _TYPE_CMD_IEEE_ED_SCAN_ccaOpt uint8_t
#define _BITPOS_CMD_IEEE_ED_SCAN_ccaOpt_ccaEnEnergy 0
#define _NBITS_CMD_IEEE_ED_SCAN_ccaOpt_ccaEnEnergy 1
#define _BITPOS_CMD_IEEE_ED_SCAN_ccaOpt_ccaEnCorr 1
#define _NBITS_CMD_IEEE_ED_SCAN_ccaOpt_ccaEnCorr 1
#define _BITPOS_CMD_IEEE_ED_SCAN_ccaOpt_ccaEnSync 2
#define _NBITS_CMD_IEEE_ED_SCAN_ccaOpt_ccaEnSync 1
#define _BITPOS_CMD_IEEE_ED_SCAN_ccaOpt_ccaCorrOp 3
#define _NBITS_CMD_IEEE_ED_SCAN_ccaOpt_ccaCorrOp 1
#define _BITPOS_CMD_IEEE_ED_SCAN_ccaOpt_ccaSyncOp 4
#define _NBITS_CMD_IEEE_ED_SCAN_ccaOpt_ccaSyncOp 1
#define _BITPOS_CMD_IEEE_ED_SCAN_ccaOpt_ccaCorrThr 5
#define _NBITS_CMD_IEEE_ED_SCAN_ccaOpt_ccaCorrThr 2
#define _POSITION_CMD_IEEE_ED_SCAN_ccaRssiThr 16
#define _TYPE_CMD_IEEE_ED_SCAN_ccaRssiThr int8_t
#define _POSITION_CMD_IEEE_ED_SCAN_maxRssi 18
#define _TYPE_CMD_IEEE_ED_SCAN_maxRssi int8_t
#define _POSITION_CMD_IEEE_ED_SCAN_endTrigger 19
#define _TYPE_CMD_IEEE_ED_SCAN_endTrigger uint8_t
#define _BITPOS_CMD_IEEE_ED_SCAN_endTrigger_triggerType 0
#define _NBITS_CMD_IEEE_ED_SCAN_endTrigger_triggerType 4
#define _BITPOS_CMD_IEEE_ED_SCAN_endTrigger_bEnaCmd 4
#define _NBITS_CMD_IEEE_ED_SCAN_endTrigger_bEnaCmd 1
#define _BITPOS_CMD_IEEE_ED_SCAN_endTrigger_triggerNo 5
#define _NBITS_CMD_IEEE_ED_SCAN_endTrigger_triggerNo 2
#define _BITPOS_CMD_IEEE_ED_SCAN_endTrigger_pastTrig 7
#define _NBITS_CMD_IEEE_ED_SCAN_endTrigger_pastTrig 1
#define _POSITION_CMD_IEEE_ED_SCAN_endTime 20
#define _TYPE_CMD_IEEE_ED_SCAN_endTime ratmr_t
#define _SIZEOF_CMD_IEEE_ED_SCAN 24
#define _POSITION_CMD_IEEE_TX_txOpt 14
#define _TYPE_CMD_IEEE_TX_txOpt uint8_t
#define _BITPOS_CMD_IEEE_TX_txOpt_bIncludePhyHdr 0
#define _NBITS_CMD_IEEE_TX_txOpt_bIncludePhyHdr 1
#define _BITPOS_CMD_IEEE_TX_txOpt_bIncludeCrc 1
#define _NBITS_CMD_IEEE_TX_txOpt_bIncludeCrc 1
#define _BITPOS_CMD_IEEE_TX_txOpt_payloadLenMsb 3
#define _NBITS_CMD_IEEE_TX_txOpt_payloadLenMsb 5
#define _POSITION_CMD_IEEE_TX_payloadLen 15
#define _TYPE_CMD_IEEE_TX_payloadLen uint8_t
#define _POSITION_CMD_IEEE_TX_pPayload 16
#define _TYPE_CMD_IEEE_TX_pPayload uint8_t*
#define _POSITION_CMD_IEEE_TX_timeStamp 20
#define _TYPE_CMD_IEEE_TX_timeStamp ratmr_t
#define _SIZEOF_CMD_IEEE_TX 24
#define _POSITION_CMD_IEEE_CSMA_randomState 14
#define _TYPE_CMD_IEEE_CSMA_randomState uint16_t
#define _POSITION_CMD_IEEE_CSMA_macMaxBE 16
#define _TYPE_CMD_IEEE_CSMA_macMaxBE uint8_t
#define _POSITION_CMD_IEEE_CSMA_macMaxCSMABackoffs 17
#define _TYPE_CMD_IEEE_CSMA_macMaxCSMABackoffs uint8_t
#define _POSITION_CMD_IEEE_CSMA_csmaConfig 18
#define _TYPE_CMD_IEEE_CSMA_csmaConfig uint8_t
#define _BITPOS_CMD_IEEE_CSMA_csmaConfig_initCW 0
#define _NBITS_CMD_IEEE_CSMA_csmaConfig_initCW 5
#define _BITPOS_CMD_IEEE_CSMA_csmaConfig_bSlotted 5
#define _NBITS_CMD_IEEE_CSMA_csmaConfig_bSlotted 1
#define _BITPOS_CMD_IEEE_CSMA_csmaConfig_rxOffMode 6
#define _NBITS_CMD_IEEE_CSMA_csmaConfig_rxOffMode 2
#define _POSITION_CMD_IEEE_CSMA_NB 19
#define _TYPE_CMD_IEEE_CSMA_NB uint8_t
#define _POSITION_CMD_IEEE_CSMA_BE 20
#define _TYPE_CMD_IEEE_CSMA_BE uint8_t
#define _POSITION_CMD_IEEE_CSMA_remainingPeriods 21
#define _TYPE_CMD_IEEE_CSMA_remainingPeriods uint8_t
#define _POSITION_CMD_IEEE_CSMA_lastRssi 22
#define _TYPE_CMD_IEEE_CSMA_lastRssi int8_t
#define _POSITION_CMD_IEEE_CSMA_endTrigger 23
#define _TYPE_CMD_IEEE_CSMA_endTrigger uint8_t
#define _BITPOS_CMD_IEEE_CSMA_endTrigger_triggerType 0
#define _NBITS_CMD_IEEE_CSMA_endTrigger_triggerType 4
#define _BITPOS_CMD_IEEE_CSMA_endTrigger_bEnaCmd 4
#define _NBITS_CMD_IEEE_CSMA_endTrigger_bEnaCmd 1
#define _BITPOS_CMD_IEEE_CSMA_endTrigger_triggerNo 5
#define _NBITS_CMD_IEEE_CSMA_endTrigger_triggerNo 2
#define _BITPOS_CMD_IEEE_CSMA_endTrigger_pastTrig 7
#define _NBITS_CMD_IEEE_CSMA_endTrigger_pastTrig 1
#define _POSITION_CMD_IEEE_CSMA_lastTimeStamp 24
#define _TYPE_CMD_IEEE_CSMA_lastTimeStamp ratmr_t
#define _POSITION_CMD_IEEE_CSMA_endTime 28
#define _TYPE_CMD_IEEE_CSMA_endTime ratmr_t
#define _SIZEOF_CMD_IEEE_CSMA 32
#define _POSITION_CMD_IEEE_RX_ACK_seqNo 14
#define _TYPE_CMD_IEEE_RX_ACK_seqNo uint8_t
#define _POSITION_CMD_IEEE_RX_ACK_endTrigger 15
#define _TYPE_CMD_IEEE_RX_ACK_endTrigger uint8_t
#define _BITPOS_CMD_IEEE_RX_ACK_endTrigger_triggerType 0
#define _NBITS_CMD_IEEE_RX_ACK_endTrigger_triggerType 4
#define _BITPOS_CMD_IEEE_RX_ACK_endTrigger_bEnaCmd 4
#define _NBITS_CMD_IEEE_RX_ACK_endTrigger_bEnaCmd 1
#define _BITPOS_CMD_IEEE_RX_ACK_endTrigger_triggerNo 5
#define _NBITS_CMD_IEEE_RX_ACK_endTrigger_triggerNo 2
#define _BITPOS_CMD_IEEE_RX_ACK_endTrigger_pastTrig 7
#define _NBITS_CMD_IEEE_RX_ACK_endTrigger_pastTrig 1
#define _POSITION_CMD_IEEE_RX_ACK_endTime 16
#define _TYPE_CMD_IEEE_RX_ACK_endTime ratmr_t
#define _SIZEOF_CMD_IEEE_RX_ACK 20
#define _SIZEOF_CMD_IEEE_ABORT_BG 14
#define _POSITION_CMD_IEEE_MOD_CCA_newCcaOpt 2
#define _TYPE_CMD_IEEE_MOD_CCA_newCcaOpt uint8_t
#define _BITPOS_CMD_IEEE_MOD_CCA_newCcaOpt_ccaEnEnergy 0
#define _NBITS_CMD_IEEE_MOD_CCA_newCcaOpt_ccaEnEnergy 1
#define _BITPOS_CMD_IEEE_MOD_CCA_newCcaOpt_ccaEnCorr 1
#define _NBITS_CMD_IEEE_MOD_CCA_newCcaOpt_ccaEnCorr 1
#define _BITPOS_CMD_IEEE_MOD_CCA_newCcaOpt_ccaEnSync 2
#define _NBITS_CMD_IEEE_MOD_CCA_newCcaOpt_ccaEnSync 1
#define _BITPOS_CMD_IEEE_MOD_CCA_newCcaOpt_ccaCorrOp 3
#define _NBITS_CMD_IEEE_MOD_CCA_newCcaOpt_ccaCorrOp 1
#define _BITPOS_CMD_IEEE_MOD_CCA_newCcaOpt_ccaSyncOp 4
#define _NBITS_CMD_IEEE_MOD_CCA_newCcaOpt_ccaSyncOp 1
#define _BITPOS_CMD_IEEE_MOD_CCA_newCcaOpt_ccaCorrThr 5
#define _NBITS_CMD_IEEE_MOD_CCA_newCcaOpt_ccaCorrThr 2
#define _POSITION_CMD_IEEE_MOD_CCA_newCcaRssiThr 3
#define _TYPE_CMD_IEEE_MOD_CCA_newCcaRssiThr int8_t
#define _SIZEOF_CMD_IEEE_MOD_CCA 4
#define _POSITION_CMD_IEEE_MOD_FILT_newFrameFiltOpt 2
#define _TYPE_CMD_IEEE_MOD_FILT_newFrameFiltOpt uint16_t
#define _BITPOS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_frameFiltEn 0
#define _NBITS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_frameFiltEn 1
#define _BITPOS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_frameFiltStop 1
#define _NBITS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_frameFiltStop 1
#define _BITPOS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_autoAckEn 2
#define _NBITS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_autoAckEn 1
#define _BITPOS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_slottedAckEn 3
#define _NBITS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_slottedAckEn 1
#define _BITPOS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_autoPendEn 4
#define _NBITS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_autoPendEn 1
#define _BITPOS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_defaultPend 5
#define _NBITS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_defaultPend 1
#define _BITPOS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_bPendDataReqOnly 6
#define _NBITS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_bPendDataReqOnly 1
#define _BITPOS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_bPanCoord 7
#define _NBITS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_bPanCoord 1
#define _BITPOS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_maxFrameVersion 8
#define _NBITS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_maxFrameVersion 2
#define _BITPOS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_fcfReservedMask 10
#define _NBITS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_fcfReservedMask 3
#define _BITPOS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_modifyFtFilter 13
#define _NBITS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_modifyFtFilter 2
#define _BITPOS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_bStrictLenFilter 15
#define _NBITS_CMD_IEEE_MOD_FILT_newFrameFiltOpt_bStrictLenFilter 1
#define _POSITION_CMD_IEEE_MOD_FILT_newFrameTypes 4
#define _TYPE_CMD_IEEE_MOD_FILT_newFrameTypes uint8_t
#define _BITPOS_CMD_IEEE_MOD_FILT_newFrameTypes_bAcceptFt0Beacon 0
#define _NBITS_CMD_IEEE_MOD_FILT_newFrameTypes_bAcceptFt0Beacon 1
#define _BITPOS_CMD_IEEE_MOD_FILT_newFrameTypes_bAcceptFt1Data 1
#define _NBITS_CMD_IEEE_MOD_FILT_newFrameTypes_bAcceptFt1Data 1
#define _BITPOS_CMD_IEEE_MOD_FILT_newFrameTypes_bAcceptFt2Ack 2
#define _NBITS_CMD_IEEE_MOD_FILT_newFrameTypes_bAcceptFt2Ack 1
#define _BITPOS_CMD_IEEE_MOD_FILT_newFrameTypes_bAcceptFt3MacCmd 3
#define _NBITS_CMD_IEEE_MOD_FILT_newFrameTypes_bAcceptFt3MacCmd 1
#define _BITPOS_CMD_IEEE_MOD_FILT_newFrameTypes_bAcceptFt4Reserved 4
#define _NBITS_CMD_IEEE_MOD_FILT_newFrameTypes_bAcceptFt4Reserved 1
#define _BITPOS_CMD_IEEE_MOD_FILT_newFrameTypes_bAcceptFt5Reserved 5
#define _NBITS_CMD_IEEE_MOD_FILT_newFrameTypes_bAcceptFt5Reserved 1
#define _BITPOS_CMD_IEEE_MOD_FILT_newFrameTypes_bAcceptFt6Reserved 6
#define _NBITS_CMD_IEEE_MOD_FILT_newFrameTypes_bAcceptFt6Reserved 1
#define _BITPOS_CMD_IEEE_MOD_FILT_newFrameTypes_bAcceptFt7Reserved 7
#define _NBITS_CMD_IEEE_MOD_FILT_newFrameTypes_bAcceptFt7Reserved 1
#define _SIZEOF_CMD_IEEE_MOD_FILT 5
#define _POSITION_CMD_IEEE_MOD_SRC_MATCH_options 2
#define _TYPE_CMD_IEEE_MOD_SRC_MATCH_options uint8_t
#define _BITPOS_CMD_IEEE_MOD_SRC_MATCH_options_bEnable 0
#define _NBITS_CMD_IEEE_MOD_SRC_MATCH_options_bEnable 1
#define _BITPOS_CMD_IEEE_MOD_SRC_MATCH_options_srcPend 1
#define _NBITS_CMD_IEEE_MOD_SRC_MATCH_options_srcPend 1
#define _BITPOS_CMD_IEEE_MOD_SRC_MATCH_options_entryType 2
#define _NBITS_CMD_IEEE_MOD_SRC_MATCH_options_entryType 1
#define _POSITION_CMD_IEEE_MOD_SRC_MATCH_entryNo 3
#define _TYPE_CMD_IEEE_MOD_SRC_MATCH_entryNo uint8_t
#define _SIZEOF_CMD_IEEE_MOD_SRC_MATCH 4
#define _SIZEOF_CMD_IEEE_ABORT_FG 2
#define _SIZEOF_CMD_IEEE_STOP_FG 2
#define _POSITION_CMD_IEEE_CCA_REQ_currentRssi 2
#define _TYPE_CMD_IEEE_CCA_REQ_currentRssi int8_t
#define _POSITION_CMD_IEEE_CCA_REQ_maxRssi 3
#define _TYPE_CMD_IEEE_CCA_REQ_maxRssi int8_t
#define _POSITION_CMD_IEEE_CCA_REQ_ccaInfo 4
#define _TYPE_CMD_IEEE_CCA_REQ_ccaInfo uint8_t
#define _BITPOS_CMD_IEEE_CCA_REQ_ccaInfo_ccaState 0
#define _NBITS_CMD_IEEE_CCA_REQ_ccaInfo_ccaState 2
#define _BITPOS_CMD_IEEE_CCA_REQ_ccaInfo_ccaEnergy 2
#define _NBITS_CMD_IEEE_CCA_REQ_ccaInfo_ccaEnergy 2
#define _BITPOS_CMD_IEEE_CCA_REQ_ccaInfo_ccaCorr 4
#define _NBITS_CMD_IEEE_CCA_REQ_ccaInfo_ccaCorr 2
#define _BITPOS_CMD_IEEE_CCA_REQ_ccaInfo_ccaSync 6
#define _NBITS_CMD_IEEE_CCA_REQ_ccaInfo_ccaSync 1
#define _SIZEOF_CMD_IEEE_CCA_REQ 5
#define _POSITION_ieeeRxOutput_nTxAck 0
#define _TYPE_ieeeRxOutput_nTxAck uint8_t
#define _POSITION_ieeeRxOutput_nRxBeacon 1
#define _TYPE_ieeeRxOutput_nRxBeacon uint8_t
#define _POSITION_ieeeRxOutput_nRxData 2
#define _TYPE_ieeeRxOutput_nRxData uint8_t
#define _POSITION_ieeeRxOutput_nRxAck 3
#define _TYPE_ieeeRxOutput_nRxAck uint8_t
#define _POSITION_ieeeRxOutput_nRxMacCmd 4
#define _TYPE_ieeeRxOutput_nRxMacCmd uint8_t
#define _POSITION_ieeeRxOutput_nRxReserved 5
#define _TYPE_ieeeRxOutput_nRxReserved uint8_t
#define _POSITION_ieeeRxOutput_nRxNok 6
#define _TYPE_ieeeRxOutput_nRxNok uint8_t
#define _POSITION_ieeeRxOutput_nRxIgnored 7
#define _TYPE_ieeeRxOutput_nRxIgnored uint8_t
#define _POSITION_ieeeRxOutput_nRxBufFull 8
#define _TYPE_ieeeRxOutput_nRxBufFull uint8_t
#define _POSITION_ieeeRxOutput_lastRssi 9
#define _TYPE_ieeeRxOutput_lastRssi int8_t
#define _POSITION_ieeeRxOutput_maxRssi 10
#define _TYPE_ieeeRxOutput_maxRssi int8_t
#define _POSITION_ieeeRxOutput_beaconTimeStamp 12
#define _TYPE_ieeeRxOutput_beaconTimeStamp ratmr_t
#define _SIZEOF_ieeeRxOutput 16
#define _POSITION_shortAddrEntry_shortAddr 0
#define _TYPE_shortAddrEntry_shortAddr uint16_t
#define _POSITION_shortAddrEntry_panId 2
#define _TYPE_shortAddrEntry_panId uint16_t
#define _SIZEOF_shortAddrEntry 4
#define _POSITION_ieeeRxCorrCrc_status 0
#define _TYPE_ieeeRxCorrCrc_status uint8_t
#define _BITPOS_ieeeRxCorrCrc_status_corr 0
#define _NBITS_ieeeRxCorrCrc_status_corr 6
#define _BITPOS_ieeeRxCorrCrc_status_bIgnore 6
#define _NBITS_ieeeRxCorrCrc_status_bIgnore 1
#define _BITPOS_ieeeRxCorrCrc_status_bCrcErr 7
#define _NBITS_ieeeRxCorrCrc_status_bCrcErr 1
#define _SIZEOF_ieeeRxCorrCrc 1
#endif

View File

@ -0,0 +1,107 @@
/******************************************************************************
* Filename: ieee_mailbox.h
* Revised: $ $
* Revision: $ $
*
* Description: Definitions for IEEE 802.15.4 interface
*
* Copyright (C) 2015 Texas Instruments Incorporated - http://www.ti.com/
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* Neither the name of Texas Instruments Incorporated 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
* OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
* DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
* THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************/
#ifndef _IEEE_MAILBOX_H
#define _IEEE_MAILBOX_H
#include "mailbox.h"
/// \name CPE interrupt definitions for IEEE 802.15.4
/// Interrupt masks for the CPE interrupt in RDBELL. These are new names for interrupts in mailbox.h,
/// used for compartibility with previous versions with separate interrupt numbers.
///@{
#define IRQN_IEEE_BG_COMMAND_SUSPENDED IRQN_BG_COMMAND_SUSPENDED
#define IRQN_IEEE_TX_FRAME IRQN_TX_DONE
#define IRQN_IEEE_TX_ACK IRQN_TX_ACK
#define IRQN_IEEE_RX_FRAME IRQN_RX_OK
#define IRQN_IEEE_RX_NOK IRQN_RX_NOK
#define IRQN_IEEE_RX_IGNORED IRQN_RX_IGNORED
#define IRQN_IEEE_RX_BUF_FULL IRQN_RX_BUF_FULL
#define IRQN_IEEE_RX_ENTRY_DONE IRQN_RX_ENTRY_DONE
#define IRQ_IEEE_BG_COMMAND_SUSPENDED (1U << IRQN_IEEE_BG_COMMAND_SUSPENDED)
#define IRQ_IEEE_TX_FRAME (1U << IRQN_IEEE_TX_FRAME)
#define IRQ_IEEE_TX_ACK (1U << IRQN_IEEE_TX_ACK)
#define IRQ_IEEE_RX_FRAME (1U << IRQN_IEEE_RX_FRAME)
#define IRQ_IEEE_RX_NOK (1U << IRQN_IEEE_RX_NOK)
#define IRQ_IEEE_RX_IGNORED (1U << IRQN_IEEE_RX_IGNORED)
#define IRQ_IEEE_RX_BUF_FULL (1U << IRQN_IEEE_RX_BUF_FULL)
#define IRQ_IEEE_RX_ENTRY_DONE (1U << IRQN_IEEE_RX_ENTRY_DONE)
///@}
/// \name Radio operation status
/// Radio operation status format:
/// Bits 15:12: Protocol
/// 0010: IEEE 802.15.4
/// Bits 11:10: Type
/// 00: Not finished
/// 01: Done successfully
/// 10: Done with error
/// Bits 9:0: Identifier
/// \name Operation not finished
///@{
#define IEEE_SUSPENDED 0x2001 ///< Operation suspended
///@}
/// \name Operation finished normally
///@{
#define IEEE_DONE_OK 0x2400 ///< Operation ended normally
#define IEEE_DONE_BUSY 0x2401 ///< CSMA-CA operation ended with failure
#define IEEE_DONE_STOPPED 0x2402 ///< Operation stopped after stop command
#define IEEE_DONE_ACK 0x2403 ///< ACK packet received with pending data bit cleared
#define IEEE_DONE_ACKPEND 0x2404 ///< ACK packet received with pending data bit set
#define IEEE_DONE_TIMEOUT 0x2405 ///< Operation ended due to timeout
#define IEEE_DONE_BGEND 0x2406 ///< FG operation ended because necessary background level
///< operation ended
#define IEEE_DONE_ABORT 0x2407 ///< Operation aborted by command
///@}
/// \name Operation finished with error
///@{
#define IEEE_ERROR_PAR 0x2800 ///< Illegal parameter
#define IEEE_ERROR_NO_SETUP 0x2801 ///< Operation using Rx or Tx attemted when not in 15.4 mode
#define IEEE_ERROR_NO_FS 0x2802 ///< Operation using Rx or Tx attemted without frequency synth configured
#define IEEE_ERROR_SYNTH_PROG 0x2803 ///< Synthesizer programming failed to complete on time
#define IEEE_ERROR_RXOVF 0x2804 ///< Receiver overflowed during operation
#define IEEE_ERROR_TXUNF 0x2805 ///< Transmitter underflowed during operation
///@}
///@}
#endif

View File

@ -0,0 +1,580 @@
/******************************************************************************
* Filename: mailbox.h
* Revised: $ $
* Revision: $ $
*
* Description: Definitions for interface between system and radio CPU
*
* Copyright (C) 2015 Texas Instruments Incorporated - http://www.ti.com/
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* Neither the name of Texas Instruments Incorporated 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
* OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
* DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
* THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************/
#ifndef _MAILBOX_H
#define _MAILBOX_H
#include <stdint.h>
#include <string.h>
/// Type definition for RAT
typedef uint32_t ratmr_t;
/// Type definition for a data queue
typedef struct {
uint8_t *pCurrEntry; ///< Pointer to the data queue entry to be used, NULL for an empty queue
uint8_t *pLastEntry; ///< Pointer to the last entry in the queue, NULL for a circular queue
} dataQueue_t;
/// \name CPE interrupt definitions
/// Interrupt masks for the CPE interrupt in RDBELL.
///@{
#define IRQN_COMMAND_DONE 0 ///< Radio operation command finished
#define IRQN_LAST_COMMAND_DONE 1 ///< Last radio operation command in a chain finished
#define IRQN_FG_COMMAND_DONE 2 ///< FG level Radio operation command finished
#define IRQN_LAST_FG_COMMAND_DONE 3 ///< Last FG level radio operation command in a chain finished
#define IRQN_TX_DONE 4 ///< Packet transmitted
#define IRQN_TX_ACK 5 ///< ACK packet transmitted
#define IRQN_TX_CTRL 6 ///< Control packet transmitted
#define IRQN_TX_CTRL_ACK 7 ///< Acknowledgement received on a transmitted control packet
#define IRQN_TX_CTRL_ACK_ACK 8 ///< Acknowledgement received on a transmitted control packet, and acknowledgement transmitted for that packet
#define IRQN_TX_RETRANS 9 ///< Packet retransmitted
#define IRQN_TX_ENTRY_DONE 10 ///< Tx queue data entry state changed to Finished
#define IRQN_TX_BUFFER_CHANGED 11 ///< A buffer change is complete
#define IRQN_BG_COMMAND_SUSPENDED 12 ///< A background level radio operation command has been suspended
#define IRQN_RX_OK 16 ///< Packet received with CRC OK, payload, and not to be ignored
#define IRQN_RX_NOK 17 ///< Packet received with CRC error
#define IRQN_RX_IGNORED 18 ///< Packet received with CRC OK, but to be ignored
#define IRQN_RX_EMPTY 19 ///< Packet received with CRC OK, not to be ignored, no payload
#define IRQN_RX_CTRL 20 ///< Control packet received with CRC OK, not to be ignored
#define IRQN_RX_CTRL_ACK 21 ///< Control packet received with CRC OK, not to be ignored, then ACK sent
#define IRQN_RX_BUF_FULL 22 ///< Packet received that did not fit in the Rx queue
#define IRQN_RX_ENTRY_DONE 23 ///< Rx queue data entry changing state to Finished
#define IRQN_RX_DATA_WRITTEN 24 ///< Data written to partial read Rx buffer
#define IRQN_RX_N_DATA_WRITTEN 25 ///< Specified number of bytes written to partial read Rx buffer
#define IRQN_RX_ABORTED 26 ///< Packet reception stopped before packet was done
#define IRQN_SYNTH_NO_LOCK 28 ///< The synth has gone out of lock after calibration
#define IRQN_MODULES_UNLOCKED 29 ///< As part of the boot process, the CM0 has opened access to RF core modules and memories
#define IRQN_BOOT_DONE 30 ///< The RF core CPU boot is finished
#define IRQN_INTERNAL_ERROR 31 ///< Internal error observed
#define IRQ_COMMAND_DONE (1U << IRQN_COMMAND_DONE)
#define IRQ_LAST_COMMAND_DONE (1U << IRQN_LAST_COMMAND_DONE)
#define IRQ_FG_COMMAND_DONE (1U << IRQN_FG_COMMAND_DONE)
#define IRQ_LAST_FG_COMMAND_DONE (1U << IRQN_LAST_FG_COMMAND_DONE)
#define IRQ_TX_DONE (1U << IRQN_TX_DONE)
#define IRQ_TX_ACK (1U << IRQN_TX_ACK)
#define IRQ_TX_CTRL (1U << IRQN_TX_CTRL)
#define IRQ_TX_CTRL_ACK (1U << IRQN_TX_CTRL_ACK)
#define IRQ_TX_CTRL_ACK_ACK (1U << IRQN_TX_CTRL_ACK_ACK)
#define IRQ_TX_RETRANS (1U << IRQN_TX_RETRANS)
#define IRQ_TX_ENTRY_DONE (1U << IRQN_TX_ENTRY_DONE)
#define IRQ_TX_BUFFER_CHANGED (1U << IRQN_TX_BUFFER_CHANGED)
#define IRQ_BG_COMMAND_SUSPENDED (1U << IRQN_BG_COMMAND_SUSPENDED)
#define IRQ_RX_OK (1U << IRQN_RX_OK)
#define IRQ_RX_NOK (1U << IRQN_RX_NOK)
#define IRQ_RX_IGNORED (1U << IRQN_RX_IGNORED)
#define IRQ_RX_EMPTY (1U << IRQN_RX_EMPTY)
#define IRQ_RX_CTRL (1U << IRQN_RX_CTRL)
#define IRQ_RX_CTRL_ACK (1U << IRQN_RX_CTRL_ACK)
#define IRQ_RX_BUF_FULL (1U << IRQN_RX_BUF_FULL)
#define IRQ_RX_ENTRY_DONE (1U << IRQN_RX_ENTRY_DONE)
#define IRQ_RX_DATA_WRITTEN (1U << IRQN_RX_DATA_WRITTEN)
#define IRQ_RX_N_DATA_WRITTEN (1U << IRQN_RX_N_DATA_WRITTEN)
#define IRQ_RX_ABORTED (1U << IRQN_RX_ABORTED)
#define IRQ_SYNTH_NO_LOCK (1U << IRQN_SYNTH_NO_LOCK)
#define IRQ_MODULES_UNLOCKED (1U << IRQN_MODULES_UNLOCKED)
#define IRQ_BOOT_DONE (1U << IRQN_BOOT_DONE)
#define IRQ_INTERNAL_ERROR (1U << IRQN_INTERNAL_ERROR)
///@}
/// \name CMDSTA values
/// Values returned in result byte of CMDSTA
///@{
#define CMDSTA_Pending 0x00 ///< The command has not yet been parsed
#define CMDSTA_Done 0x01 ///< Command successfully parsed
#define CMDSTA_IllegalPointer 0x81 ///< The pointer signaled in CMDR is not valid
#define CMDSTA_UnknownCommand 0x82 ///< The command number in the command structure is unknown
#define CMDSTA_UnknownDirCommand 0x83 ///< The command number for a direct command is unknown, or the
///< command is not a direct command
#define CMDSTA_ContextError 0x85 ///< An immediate or direct command was issued in a context
///< where it is not supported
#define CMDSTA_SchedulingError 0x86 ///< A radio operation command was attempted to be scheduled
///< while another operation was already running in the RF core
#define CMDSTA_ParError 0x87 ///< There were errors in the command parameters that are parsed
///< on submission.
#define CMDSTA_QueueError 0x88 ///< An operation on a data entry queue was attempted that was
///< not supported by the queue in its current state
#define CMDSTA_QueueBusy 0x89 ///< An operation on a data entry was attempted while that entry
///< was busy
///@}
/// \name Macros for use with command definition files
/// The script create_command.pl generates header files from command and structure definitions in the
/// *_def.txt files. These are the macros to access the definitions
///@{
/// Get a field from a structure
//
/// Gets a field from a structure defined in a _def.txt file. This may be used both in assignments and
/// references (e.g. GET_FIELD(pCmd1, CMD_TEST, testParam) = GET_FIELD(pCmd2, CMD_DUMMY, dummyParam);)
/// \param[in] ptr
/// Pointer to the structure
/// \param[in] cmd
/// Name of the command or structure as defined in the _def.txt file
/// \param[in] field
/// Name of the accessed field as defined in the _def.txt file
///
#define GET_FIELD(ptr, cmd, field) \
(*((_TYPE_##cmd##_##field *) (((uint8_t *)(ptr)) + (_POSITION_##cmd##_##field))))
/// Get a field from a structure, reading as volatile
//
/// Gets a field from a structure defined in a _def.txt file, reading it as a volatile parameter, which
/// takes into account that it may be changed by the other side. This may be used both in assignments and
/// references (e.g. GET_FIELD(pCmd1, CMD_TEST, testParam) = GET_FIELD(pCmd2, CMD_DUMMY, dummyParam);)
/// \param[in] ptr
/// Pointer to the structure
/// \param[in] cmd
/// Name of the command or structure as defined in the _def.txt file
/// \param[in] field
/// Name of the accessed field as defined in the _def.txt file
///
#define GET_FIELD_V(ptr, cmd, field) \
(*((volatile _TYPE_##cmd##_##field *) (((uint8_t *)(ptr)) + (_POSITION_##cmd##_##field))))
/// Get the pointer to a field from a structure
//
/// Gets the pointer to a field from a structure defined in a _def.txt file.
/// \param[in] ptr
/// Pointer to the structure
/// \param[in] cmd
/// Name of the command or structure as defined in the _def.txt file
/// \param[in] field
/// Name of the accessed field as defined in the _def.txt file
///
#define GET_FIELD_PTR(ptr, cmd, field) \
((_TYPE_##cmd##_##field *) (((uint8_t *)(ptr)) + (_POSITION_##cmd##_##field)))
/// Get the volatile pointer to a field from a structure
//
/// Gets the volatile pointer to a field from a structure defined in a _def.txt file.
/// \param[in] ptr
/// Pointer to the structure
/// \param[in] cmd
/// Name of the command or structure as defined in the _def.txt file
/// \param[in] field
/// Name of the accessed field as defined in the _def.txt file
///
#define GET_FIELD_VPTR(ptr, cmd, field) \
((volatile _TYPE_##cmd##_##field *) (((uint8_t *)(ptr)) + (_POSITION_##cmd##_##field)))
/// Get bits from a bit field
//
/// Returns bits from a bit field defined in a _def.txt file.
/// \param[in] value
/// The value of the entire field that contains the bit field
/// \param[in] cmd
/// Name of the command or structure as defined in the _def.txt file
/// \param[in] field
/// Name of the field that contains the bit field definition as defined in the _def.txt file
/// \param[in] bitfield
/// Name of the bitfield as defined in the _def.txt file
///
#define GET_BITS(value, cmd, field, bitfield) \
(((value) >> (_BITPOS_##cmd##_##field##_##bitfield)) & \
((1U << (_NBITS_##cmd##_##field##_##bitfield)) - 1))
/// Get bits from a bit field as a signed value
//
/// Returns sign extended bits from a bit field defined in a _def.txt file.
/// \param[in] value
/// The value of the entire field that contains the bit field
/// \param[in] cmd
/// Name of the command or structure as defined in the _def.txt file
/// \param[in] field
/// Name of the field that contains the bit field definition as defined in the _def.txt file
/// \param[in] bitfield
/// Name of the bitfield as defined in the _def.txt file
///
#define GET_BITS_S(value, cmd, field, bitfield) \
(((int)(value) << (32 - ((_BITPOS_##cmd##_##field##_##bitfield) + (_NBITS_##cmd##_##field##_##bitfield)))) >> \
(32 - (_NBITS_##cmd##_##field##_##bitfield)))
/// Set bits in a bit field
//
/// Modifies a bit field defined in a _def.txt file.
/// \param[in,out] value
/// The value of the entire field that contains the bit field
/// \param[in] cmd
/// Name of the command or structure as defined in the _def.txt file
/// \param[in] field
/// Name of the field that contains the bit field definition as defined in the _def.txt file
/// \param[in] bitfield
/// Name of the bitfield as defined in the _def.txt file
/// \param[in] bvalue
/// The value to set in the bitfield
///
#define SET_BITS(value, cmd, field, bitfield, bvalue) \
(((value) = ((value) & \
(~(((1U << (_NBITS_##cmd##_##field##_##bitfield)) - 1) << (_BITPOS_##cmd##_##field##_##bitfield))) | \
((bvalue) << (_BITPOS_##cmd##_##field##_##bitfield)))))
/// Get bits from a bit field in a structure
//
/// Returns bits from a bit field in a structure defined in a _def.txt file.
/// \param[in] ptr
/// Pointer to the structure
/// \param[in] cmd
/// Name of the command or structure as defined in the _def.txt file
/// \param[in] field
/// Name of the field that contains the bit field definition as defined in the _def.txt file
/// \param[in] bitfield
/// Name of the bitfield as defined in the _def.txt file
///
#define GET_BITFIELD(ptr, cmd, field, bitfield) \
((*((_TYPE_##cmd##_##field *) ((((uint8_t *)(ptr)) + (_POSITION_##cmd##_##field)))) >> \
((_BITPOS_##cmd##_##field##_##bitfield))) & \
((1U << (_NBITS_##cmd##_##field##_##bitfield)) - 1))
/// Get bits from a bit field in a structure, reading as volatile
//
/// Returns bits from a bit field in a structure defined in a _def.txt file, reading it as a
/// volatile parameter.
/// \param[in] ptr
/// Pointer to the structure
/// \param[in] cmd
/// Name of the command or structure as defined in the _def.txt file
/// \param[in] field
/// Name of the field that contains the bit field definition as defined in the _def.txt file
/// \param[in] bitfield
/// Name of the bitfield as defined in the _def.txt file
///
#define GET_BITFIELD_V(ptr, cmd, field, bitfield) \
((*((volatile _TYPE_##cmd##_##field *) ((((uint8_t *)(ptr)) + (_POSITION_##cmd##_##field)))) >> \
((_BITPOS_##cmd##_##field##_##bitfield))) & \
((1U << (_NBITS_##cmd##_##field##_##bitfield)) - 1))
/// Set bits in a bit field in a structure
//
/// Modifies a bit field in a field in a structure defined in a _def.txt file.
/// \param[in] ptr
/// Pointer to the structure
/// \param[in] cmd
/// Name of the command or structure as defined in the _def.txt file
/// \param[in] field
/// Name of the field that contains the bit field definition as defined in the _def.txt file
/// \param[in] bitfield
/// Name of the bitfield as defined in the _def.txt file
/// \param[in] value
/// The value to set in the bitfield
///
#define SET_BITFIELD(ptr, cmd, field, bitfield, value) \
((*((_TYPE_##cmd##_##field *) (((uint8_t *)(ptr)) + (_POSITION_##cmd##_##field)))) = \
((*((_TYPE_##cmd##_##field *) (((uint8_t *)(ptr)) + (_POSITION_##cmd##_##field)))) & \
(~(((1U << (_NBITS_##cmd##_##field##_##bitfield)) - 1) << (_BITPOS_##cmd##_##field##_##bitfield))) | \
(((uint32_t)(value)) << (_BITPOS_##cmd##_##field##_##bitfield))))
/// Set bits in a bit field in a structure, reading and writing as volatile
//
/// Modifies a bit field in a field in a structure defined in a _def.txt file, accessing it as a volatile
/// parameter.
/// \param[in] ptr
/// Pointer to the structure
/// \param[in] cmd
/// Name of the command or structure as defined in the _def.txt file
/// \param[in] field
/// Name of the field that contains the bit field definition as defined in the _def.txt file
/// \param[in] bitfield
/// Name of the bitfield as defined in the _def.txt file
/// \param[in] value
/// The value to set in the bitfield
///
#define SET_BITFIELD_V(ptr, cmd, field, bitfield, value) \
((*((volatile _TYPE_##cmd##_##field *) (((uint8_t *)(ptr)) + (_POSITION_##cmd##_##field)))) = \
((*((volatile _TYPE_##cmd##_##field *) (((uint8_t *)(ptr)) + (_POSITION_##cmd##_##field)))) & \
(~(((1U << (_NBITS_##cmd##_##field##_##bitfield)) - 1) << (_BITPOS_##cmd##_##field##_##bitfield))) | \
(((uint32_t)(value)) << (_BITPOS_##cmd##_##field##_##bitfield))))
/// Get the value of specific bifield in a field with the remaining bits set to 0
//
/// Returns a bitfield so that the value of the full field can be obtained by bitwise
/// OR between these
/// \param[in] cmd
/// Name of the command or structure as defined in the _def.txt file
/// \param[in] field
/// Name of the field that contains the bit field definition as defined in the _def.txt file
/// \param[in] bitfield
/// Name of the bitfield as defined in the _def.txt file
/// \param[in] value
/// The value to use in the bitfield
///
#define BITVALUE(cmd, field, bitfield, value) \
((((uint32_t)(value)) & ((1U << (_NBITS_##cmd##_##field##_##bitfield)) - 1)) << \
(_BITPOS_##cmd##_##field##_##bitfield))
/// Get the size of a structure
//
/// Gets the size of a structure defined in a _def.txt file.
///
/// \param[in] cmd
/// Name of the command or structure as defined in the _def.txt file
///
#define SIZEOF_STRUCT(cmd) \
(_SIZEOF_##cmd)
/// Get the size of a radio operation command structure
//
/// Gets the size of a radio operation command structure defined in a _def.txt file. The difference from
/// SIZEOF_STRUCT is for legacy reasons only.
///
/// \param[in] cmd
/// Name of the command or structure as defined in the _def.txt file
///
#define SIZEOF_RADIO_OP(cmd) \
(_SIZEOF_##cmd)
/// Initializes a structure to an initialization set
//
/// Sets the value of a structure to its given initialization values
/// \param[in] ptr
/// Pointer to the structure, must be word aligned
/// \param[in] cmd
/// Name of the command or structure as defined in the _def.txt file
/// \param[in] set
/// Index of the set of initializations to use
///
#define INIT_STRUCT(ptr, cmd, set) \
(memcpy(((uint32_t *)(ptr)) + (_START_INIT_WIDX_##cmd), (__init_##cmd[(set)]), \
(_N_INIT_WORDS_##cmd) * sizeof(uint32_t)))
///@}
/// \name Macros for sending direct commands
///@{
/// Direct command with no parameter
#define CMDR_DIR_CMD(cmdId) (((cmdId) << 16) | 1)
/// Direct command with 1-byte parameter
#define CMDR_DIR_CMD_1BYTE(cmdId, par) (((cmdId) << 16) | ((par) << 8) | 1)
/// Direct command with 2-byte parameter
#define CMDR_DIR_CMD_2BYTE(cmdId, par) (((cmdId) << 16) | ((par) & 0xFFFC) | 1)
///@}
/// \name Definitions for trigger types
///@{
#define TRIG_NOW 0 ///< Triggers immediately
#define TRIG_NEVER 1 ///< Never trigs
#define TRIG_ABSTIME 2 ///< Trigs at an absolute time
#define TRIG_REL_SUBMIT 3 ///< Trigs at a time relative to the command was submitted
#define TRIG_REL_START 4 ///< Trigs at a time relative to the command started
#define TRIG_REL_PREVSTART 5 ///< Trigs at a time relative to the previous command in the chain started
#define TRIG_REL_FIRSTSTART 6 ///< Trigs at a time relative to the first command in the chain started
#define TRIG_REL_PREVEND 7 ///< Trigs at a time relative to the previous command in the chain ended
#define TRIG_REL_EVT1 8 ///< Trigs at a time relative to the context defined "Event 1"
#define TRIG_REL_EVT2 9 ///< Trigs at a time relative to the context defined "Event 2"
#define TRIG_EXTERNAL 10 ///< Trigs at an external event to the radio timer
#define TRIG_PAST_BM 0x80 ///< Bitmask for setting pastTrig bit in order to trig immediately if
///< trigger happened in the past
///@}
/// \name Definitions for conditional execution
///@{
#define COND_ALWAYS 0 ///< Always run next command (except in case of Abort)
#define COND_NEVER 1 ///< Never run next command
#define COND_STOP_ON_FALSE 2 ///< Run next command if this command returned True, stop if it returned
///< False
#define COND_STOP_ON_TRUE 3 ///< Stop if this command returned True, run next command if it returned
///< False
#define COND_SKIP_ON_FALSE 4 ///< Run next command if this command returned True, skip a number of
///< commands if it returned False
#define COND_SKIP_ON_TRUE 5 ///< Skip a number of commands if this command returned True, run next
///< command if it returned False
///@}
/// \name Radio operation status
/// Radio operation status format:
///@{
/// \name Operation not finished
///@{
#define IDLE 0x0000 ///< Operation not started
#define PENDING 0x0001 ///< Start of command is pending
#define ACTIVE 0x0002 ///< Running
#define SKIPPED 0x0003 ///< Operation skipped due to condition in another command
///@}
/// \name Operation finished normally
///@{
#define DONE_OK 0x0400 ///< Operation ended normally
#define DONE_COUNTDOWN 0x0401 ///< Counter reached zero
#define DONE_RXERR 0x0402 ///< Operation ended with CRC error
#define DONE_TIMEOUT 0x0403 ///< Operation ended with timeout
#define DONE_STOPPED 0x0404 ///< Operation stopped after CMD_STOP command
#define DONE_ABORT 0x0405 ///< Operation aborted by CMD_ABORT command
#define DONE_FAILED 0x0406 ///< Scheduled immediate command failed
///@}
/// \name Operation finished with error
///@{
#define ERROR_PAST_START 0x0800 ///< The start trigger occurred in the past
#define ERROR_START_TRIG 0x0801 ///< Illegal start trigger parameter
#define ERROR_CONDITION 0x0802 ///< Illegal condition for next operation
#define ERROR_PAR 0x0803 ///< Error in a command specific parameter
#define ERROR_POINTER 0x0804 ///< Invalid pointer to next operation
#define ERROR_CMDID 0x0805 ///< Next operation has a command ID that is undefined or not a radio
///< operation command
#define ERROR_WRONG_BG 0x0806 ///< FG level command not compatible with running BG level command
#define ERROR_NO_SETUP 0x0807 ///< Operation using Rx or Tx attemted without CMD_RADIO_SETUP
#define ERROR_NO_FS 0x0808 ///< Operation using Rx or Tx attemted without frequency synth configured
#define ERROR_SYNTH_PROG 0x0809 ///< Synthesizer calibration failed
#define ERROR_TXUNF 0x080A ///< Tx underflow observed
#define ERROR_RXOVF 0x080B ///< Rx overflow observed
#define ERROR_NO_RX 0x080C ///< Attempted to access data from Rx when no such data was yet received
#define ERROR_PENDING 0x080D ///< Command submitted in the future with another command at different level pending
///@}
///@}
/// \name Data entry types
///@{
#define DATA_ENTRY_TYPE_GEN 0 ///< General type: Tx entry or single element Rx entry
#define DATA_ENTRY_TYPE_MULTI 1 ///< Multi-element Rx entry type
#define DATA_ENTRY_TYPE_PTR 2 ///< Pointer entry type
#define DATA_ENTRY_TYPE_PARTIAL 3 ///< Partial read entry type
///@
/// \name Data entry statuses
///@{
#define DATA_ENTRY_PENDING 0 ///< Entry not yet used
#define DATA_ENTRY_ACTIVE 1 ///< Entry in use by radio CPU
#define DATA_ENTRY_BUSY 2 ///< Entry being updated
#define DATA_ENTRY_FINISHED 3 ///< Radio CPU is finished accessing the entry
#define DATA_ENTRY_UNFINISHED 4 ///< Radio CPU is finished accessing the entry, but packet could not be finished
///@}
/// Difference between length and size of rxData field in multi-element Rx entry
#define DATA_ENTRY_MULTI_LEN_OFFSET (_POSITION_dataEntry_rxData - _POSITION_dataEntry_data)
/// \name Macros for RF register override
///@{
/// Macro for ADI half-size value-mask combination
#define ADI_VAL_MASK(addr, mask, value) \
(((addr) & 1) ? (((mask) & 0x0F) | (((value) & 0x0F) << 4)) : \
((((mask) & 0x0F) << 4) | ((value) & 0x0F)))
/// 32-bit write of 16-bit value
#define HW_REG_OVERRIDE(addr, val) ((((uintptr_t) (addr)) & 0xFFFC) | ((uint32_t)(val) << 16))
/// ADI register, full-size write
#define ADI_REG_OVERRIDE(adiNo, addr, val) (2 | ((uint32_t)(val) << 16) | \
(((addr) & 0x3F) << 24) | (((adiNo) ? 1U : 0) << 31))
/// 2 ADI registers, full-size write
#define ADI_2REG_OVERRIDE(adiNo, addr, val, addr2, val2) \
(2 | ((uint32_t)(val2) << 2) | (((addr2) & 0x3F) << 10) | ((uint32_t)(val) << 16) | \
(((addr) & 0x3F) << 24) | (((adiNo) ? 1U : 0) << 31))
/// ADI register, half-size read-modify-write
#define ADI_HALFREG_OVERRIDE(adiNo, addr, mask, val) (2 | (ADI_VAL_MASK(addr, mask, val) << 16) | \
(((addr) & 0x3F) << 24) | (1U << 30) | (((adiNo) ? 1U : 0) << 31))
/// 2 ADI registers, half-size read-modify-write
#define ADI_2HALFREG_OVERRIDE(adiNo, addr, mask, val, addr2, mask2, val2) \
(2 | (ADI_VAL_MASK(addr2, mask2, val2) << 2) | (((addr2) & 0x3F) << 10) | \
(ADI_VAL_MASK(addr, mask, val) << 16) | (((addr) & 0x3F) << 24) | (1U << 30) | (((adiNo) ? 1U : 0) << 31))
/// 16-bit SW register as defined in radio_par_def.txt
#define SW_REG_OVERRIDE(cmd, field, val) (3 | ((_POSITION_##cmd##_##field) << 4) | ((uint32_t)(val) << 16))
/// SW register as defined in radio_par_def.txt with added index (for use with registers > 16 bits).
#define SW_REG_IND_OVERRIDE(cmd, field, offset, val) (3 | \
(((_POSITION_##cmd##_##field) + ((offset) << 1)) << 4) | ((uint32_t)(val) << 16))
/// 8-bit SW register as defined in radio_par_def.txt
#define SW_REG_BYTE_OVERRIDE(cmd, field, val) (0x8003 | ((_POSITION_##cmd##_##field) << 4) | \
((uint32_t)(val) << 16))
/// Two 8-bit SW registers as defined in radio_par_def.txt; the one given by field and the next byte.
#define SW_REG_2BYTE_OVERRIDE(cmd, field, val0, val1) (3 | (((_POSITION_##cmd##_##field) & 0xFFFE) << 4) | \
(((uint32_t)(val0) << 16) & 0x00FF0000) | ((uint32_t)(val1) << 24))
#define HW16_ARRAY_OVERRIDE(addr, length) (1 | (((uintptr_t) (addr)) & 0xFFFC) | ((uint32_t)(length) << 16))
#define HW32_ARRAY_OVERRIDE(addr, length) (1 | (((uintptr_t) (addr)) & 0xFFFC) | \
((uint32_t)(length) << 16) | (1U << 30))
#define ADI_ARRAY_OVERRIDE(adiNo, addr, bHalfSize, length) (1 | ((((addr) & 0x3F) << 2)) | \
((!!(bHalfSize)) << 8) | ((!!(adiNo)) << 9) | ((uint32_t)(length) << 16) | (2U << 30))
#define SW_ARRAY_OVERRIDE(cmd, firstfield, length) (1 | (((_POSITION_##cmd##_##firstfield)) << 2) | \
((uint32_t)(length) << 16) | (3U << 30))
#define MCE_RFE_OVERRIDE(bMceRam, mceRomBank, mceMode, bRfeRam, rfeRomBank, rfeMode) \
(7 | ((!!(bMceRam)) << 8) | (((mceRomBank) & 0x07) << 9) | ((!!(bRfeRam)) << 12) | (((rfeRomBank) & 0x07) << 13) | \
(((mceMode) & 0x00FF) << 16) | (((rfeMode) & 0x00FF) << 24))
#define BAW_OVERRIDE(freqOffset) (0x000B | ((freqOffset) << 16))
#define NEW_OVERRIDE_SEGMENT(address) (((((uintptr_t)(address)) & 0x03FFFFFC) << 6) | 0x000F | \
(((((uintptr_t)(address) >> 24) == 0x20) ? 0x01 : \
(((uintptr_t)(address) >> 24) == 0x21) ? 0x02 : \
(((uintptr_t)(address) >> 24) == 0xA0) ? 0x03 : \
(((uintptr_t)(address) >> 24) == 0x00) ? 0x04 : \
(((uintptr_t)(address) >> 24) == 0x10) ? 0x05 : \
(((uintptr_t)(address) >> 24) == 0x11) ? 0x06 : \
(((uintptr_t)(address) >> 24) == 0x40) ? 0x07 : \
(((uintptr_t)(address) >> 24) == 0x50) ? 0x08 : \
0x09) << 4)) // Use illegal value for illegal address range
/// End of string for override register
#define END_OVERRIDE 0xFFFFFFFF
#define FWPAR_8BIT_ADDR(cmd, field) (0x1800 | (_POSITION_##cmd##_##field))
#define FWPAR_16BIT_ADDR(cmd, field) (0x1000 | (_POSITION_##cmd##_##field))
#define FWPAR_32BIT_ADDR(cmd, field) (0x0000 | (_POSITION_##cmd##_##field))
/// ADI address-value pair
#define ADI_ADDR_VAL(addr, value) ((((addr) & 0x7F) << 8) | ((value) & 0xFF))
#define ADI_ADDR_VAL_MASK(addr, mask, value) ((((addr) & 0x7F) << 8) | ADI_VAL_MASK(addr, mask, value))
/// Low half-word
#define LOWORD(value) ((value) & 0xFFFF)
/// High half-word
#define HIWORD(value) ((value) >> 16)
///@}
#endif

51
cpu/cc26xx/dev/uart1.h Normal file
View File

@ -0,0 +1,51 @@
/*
* Copyright (c) 2012, 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-uart
* @{
*
* \file
* This file really only exists because some examples rely on it.
*
* For instance, some examples do uart1_set_input(f). We re-write this to
* uart_set_input
*/
#ifndef UART1_H_
#define UART1_H_
#include "dev/cc26xx-uart.h"
#define BAUD2UBR(x) x
#define uart1_set_input(f) cc26xx_uart_set_input(f)
#endif /* UART1_H_ */
/** @} */

View File

@ -0,0 +1,54 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
#include "inc/hw_types.h"
#include "inc/hw_memmap.h"
#include "inc/hw_cpu_scs.h"
/*---------------------------------------------------------------------------*/
#define fault_handlers_hard_fault_isr FaultISR
/*---------------------------------------------------------------------------*/
void
fault_handlers_hard_fault_isr(void)
{
/*
* Workaround for (Im)precise Bus Faults caused under unknown circumstances,
* likely by access to RFC registers while the RF PD is off (which is
* something that should never happen because we do in fact check before
* accessing)
*/
if((HWREG(CPU_SCS_BASE + CPU_SCS_O_CFSR) == CPU_SCS_CFSR_IMPRECISERR) ||
(HWREG(CPU_SCS_BASE + CPU_SCS_O_CFSR) & CPU_SCS_CFSR_PRECISERR)){
/* ToDo: Check BFARVALID and then BFAR to filter down even further */
return;
}
while(1);
}
/*---------------------------------------------------------------------------*/

90
cpu/cc26xx/ieee-addr.c Normal file
View File

@ -0,0 +1,90 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup cc26xx-ieee-addr
* @{
*
* \file
* Driver for the CC26xx IEEE addresses
*/
/*---------------------------------------------------------------------------*/
#include "contiki-conf.h"
#include "net/linkaddr.h"
#include "ieee-addr.h"
#include <stdint.h>
#include <string.h>
/*---------------------------------------------------------------------------*/
void
ieee_addr_cpy_to(uint8_t *dst, uint8_t len)
{
if(IEEE_ADDR_CONF_HARDCODED) {
uint8_t ieee_addr_hc[8] = IEEE_ADDR_CONF_ADDRESS;
memcpy(dst, &ieee_addr_hc[8 - len], len);
} else {
int i;
/* Reading from primary location... */
uint8_t *location = (uint8_t *)IEEE_ADDR_LOCATION_PRIMARY;
/*
* ...unless we can find a byte != 0xFF in secondary
*
* Intentionally checking all 8 bytes here instead of len, because we
* are checking validity of the entire IEEE address irrespective of the
* actual number of bytes the caller wants to copy over.
*/
for(i = 0; i < 8; i++) {
if(((uint8_t *)IEEE_ADDR_LOCATION_SECONDARY)[i] != 0xFF) {
/* A byte in the secondary location is not 0xFF. Use the secondary */
location = (uint8_t *)IEEE_ADDR_LOCATION_SECONDARY;
break;
}
}
/*
* We have chosen what address to read the IEEE address from. Do so,
* inverting byte order
*/
for(i = 0; i < len; i++) {
dst[i] = location[len - 1 - i];
}
}
#if IEEE_ADDR_NODE_ID
dst[len - 1] = IEEE_ADDR_NODE_ID & 0xFF;
dst[len - 2] = IEEE_ADDR_NODE_ID >> 8;
#endif
}
/*---------------------------------------------------------------------------*/
/** @} */

105
cpu/cc26xx/ieee-addr.h Normal file
View File

@ -0,0 +1,105 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup cc26xx
* @{
*
* \defgroup cc26xx-ieee-addr CC26xx IEEE Address Control
*
* Driver for the retrieval of an IEEE address from flash
*
* The user can specify a hardcoded IEEE address through the
* IEEE_ADDR_CONF_HARDCODED configuration macro.
*
* If the user does not hard-code an address, then one will be read from either
* the primary location (InfoPage) or from the secondary location (on flash).
*
* In order to allow the user to easily program nodes with addresses, the
* secondary location is given priority: If it contains a valid address then
* it will be chosen in favour of the one on InfoPage.
*
* In this context, an address is valid if at least one of the 8 bytes does not
* equal 0xFF. If all 8 bytes are 0xFF, then the primary location will be used.
*
* In all cases, the address is assumed to be written little-endian.
*
* Lastly, it is possible to override the 2 LSB's of the address by using the
* NODE_ID make variable.
* @{
*
* \file
* Header file with register and macro declarations for the cc26xx IEEE address
* driver
*/
/*---------------------------------------------------------------------------*/
#ifndef IEEE_ADDR_H_
#define IEEE_ADDR_H_
/*---------------------------------------------------------------------------*/
#include "contiki-conf.h"
#include <stdint.h>
/*---------------------------------------------------------------------------*/
/**
* \name IEEE address locations
*
* The address of the secondary location can be configured by the platform
* or example
*
* @{
*/
#define IEEE_ADDR_LOCATION_PRIMARY 0x500012F0 /**< Primary IEEE address location */
#ifdef IEEE_ADDR_CONF_LOCATION_SECONDARY
#define IEEE_ADDR_LOCATION_SECONDARY IEEE_ADDR_CONF_LOCATION_SECONDARY
#else
#define IEEE_ADDR_LOCATION_SECONDARY 0x0001FFC8 /**< Secondary IEEE address location */
#endif
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \brief Copy the node's IEEE address to a destination memory area
* \param dst A pointer to the destination area where the IEEE address is to be
* written
* \param len The number of bytes to write to destination area
*
* This function will copy \e len LS bytes and it will invert byte order in
* the process. The factory address on devices is normally little-endian,
* therefore you should expect dst to store the address in a big-endian order.
*/
void ieee_addr_cpy_to(uint8_t *dst, uint8_t len);
/*---------------------------------------------------------------------------*/
#endif /* IEEE_ADDR_H_ */
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
*/

408
cpu/cc26xx/lpm.c Normal file
View File

@ -0,0 +1,408 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup cc26xx-lpm
* @{
*
* Implementation of CC26xx low-power operation functionality
*
* @{
*
* \file
* Driver for CC26xx's low-power operation
*/
/*---------------------------------------------------------------------------*/
#include "prcm.h"
#include "contiki-conf.h"
#include "ti-lib.h"
#include "lpm.h"
#include "sys/energest.h"
#include "lib/list.h"
#include "dev/leds.h"
#include "dev/watchdog.h"
#include "dev/cc26xx-rtc.h"
/*---------------------------------------------------------------------------*/
#if ENERGEST_CONF_ON
static unsigned long irq_energest = 0;
#define ENERGEST_IRQ_SAVE(a) do { \
a = energest_type_time(ENERGEST_TYPE_IRQ); } while(0)
#define ENERGEST_IRQ_RESTORE(a) do { \
energest_type_set(ENERGEST_TYPE_IRQ, a); } while(0)
#else
#define ENERGEST_IRQ_SAVE(a) do {} while(0)
#define ENERGEST_IRQ_RESTORE(a) do {} while(0)
#endif
/*---------------------------------------------------------------------------*/
LIST(modules_list);
/*---------------------------------------------------------------------------*/
/* Control what power domains we are allow to run under what mode */
LIST(power_domain_locks_list);
/* PDs that may stay on in deep sleep */
#define LOCKABLE_DOMAINS ((uint32_t)(PRCM_DOMAIN_SERIAL | PRCM_DOMAIN_PERIPH))
/*---------------------------------------------------------------------------*/
/*
* Don't consider standby mode if the next AON RTC event is scheduled to fire
* in less than STANDBY_MIN_DURATION rtimer ticks
*/
#define STANDBY_MIN_DURATION (RTIMER_SECOND >> 8)
/*---------------------------------------------------------------------------*/
/* Variables used by the power on/off (Power mode: SHUTDOWN) functionality */
static uint8_t shutdown_requested;
static uint32_t pin;
/*---------------------------------------------------------------------------*/
void
lpm_pd_lock_obtain(lpm_power_domain_lock_t *lock, uint32_t domains)
{
/* We only accept locks for specific PDs */
domains &= LOCKABLE_DOMAINS;
if(domains == 0) {
return;
}
lock->domains = domains;
list_add(power_domain_locks_list, lock);
}
/*---------------------------------------------------------------------------*/
void
lpm_pd_lock_release(lpm_power_domain_lock_t *lock)
{
lock->domains = 0;
list_remove(power_domain_locks_list, lock);
}
/*---------------------------------------------------------------------------*/
void
lpm_shutdown(uint32_t wakeup_pin)
{
shutdown_requested = 1;
pin = wakeup_pin;
}
/*---------------------------------------------------------------------------*/
static void
shutdown_now(void)
{
lpm_registered_module_t *module;
int i;
rtimer_clock_t t0;
uint32_t io_cfg = (IOC_STD_INPUT & ~IOC_IOPULL_M) | IOC_IOPULL_UP |
IOC_WAKE_ON_LOW;
for(module = list_head(modules_list); module != NULL;
module = module->next) {
if(module->shutdown) {
module->shutdown(LPM_MODE_SHUTDOWN);
}
}
leds_off(LEDS_ALL);
for(i = 0; i < 5; i++) {
t0 = RTIMER_NOW();
leds_toggle(LEDS_ALL);
while(RTIMER_CLOCK_LT(RTIMER_NOW(), (t0 + (RTIMER_SECOND >> 3))));
}
leds_off(LEDS_ALL);
ti_lib_gpio_dir_mode_set((1 << pin), GPIO_DIR_MODE_IN);
ti_lib_ioc_port_configure_set(pin, IOC_PORT_GPIO, io_cfg);
ti_lib_pwr_ctrl_state_set(LPM_MODE_SHUTDOWN);
}
/*---------------------------------------------------------------------------*/
/*
* We'll get called on three occasions:
* - While running
* - While sleeping
* - While deep sleeping
*
* For the former two, we don't need to do anything. For the latter, we
* notify all modules that we're back on and rely on them to restore clocks
* and power domains as required.
*/
void
lpm_wake_up()
{
lpm_registered_module_t *module;
/* Remember IRQ energest for next pass */
ENERGEST_IRQ_SAVE(irq_energest);
ENERGEST_ON(ENERGEST_TYPE_CPU);
ENERGEST_OFF(ENERGEST_TYPE_LPM);
/* Sync so that we get the latest values before adjusting recharge settings */
ti_lib_sys_ctrl_aon_sync();
/* Adjust recharge settings */
ti_lib_sys_ctrl_adjust_recharge_after_power_down();
/*
* Release the request to the uLDO
* This is likely not required, since the switch to GLDO/DCDC is automatic
* when coming back from deep sleep
*/
ti_lib_prcm_mcu_uldo_configure(false);
/* Turn on cache again */
ti_lib_vims_mode_set(VIMS_BASE, VIMS_MODE_ENABLED);
ti_lib_prcm_retention_enable(PRCM_DOMAIN_VIMS);
ti_lib_aon_ioc_freeze_disable();
ti_lib_sys_ctrl_aon_sync();
/* Power up AUX and allow it to go to sleep */
ti_lib_aon_wuc_aux_wakeup_event(AONWUC_AUX_ALLOW_SLEEP);
/* Notify all registered modules that we've just woken up */
for(module = list_head(modules_list); module != NULL;
module = module->next) {
if(module->wakeup) {
module->wakeup();
}
}
}
/*---------------------------------------------------------------------------*/
void
lpm_drop()
{
lpm_registered_module_t *module;
lpm_power_domain_lock_t *lock;
uint8_t max_pm = LPM_MODE_MAX_SUPPORTED;
uint8_t module_pm;
uint32_t domains = LOCKABLE_DOMAINS;
if(shutdown_requested) {
shutdown_now();
}
if(RTIMER_CLOCK_LT(cc26xx_rtc_get_next_trigger(),
RTIMER_NOW() + STANDBY_MIN_DURATION)) {
lpm_sleep();
return;
}
/* Collect max allowed PM permission from interested modules */
for(module = list_head(modules_list); module != NULL;
module = module->next) {
if(module->request_max_pm) {
module_pm = module->request_max_pm();
if(module_pm < max_pm) {
max_pm = module_pm;
}
}
}
/* Check if any events fired during this process. Last chance to abort */
if(process_nevents()) {
return;
}
/* Drop */
if(max_pm == LPM_MODE_SLEEP) {
lpm_sleep();
} else {
/* Critical. Don't get interrupted! */
ti_lib_int_master_disable();
/*
* Notify all registered modules that we are dropping to mode X. We do not
* need to do this for simple sleep.
*
* This is a chance for modules to delay us a little bit until an ongoing
* operation has finished (e.g. uart TX) or to configure themselves for
* deep sleep.
*/
for(module = list_head(modules_list); module != NULL;
module = module->next) {
if(module->shutdown) {
module->shutdown(max_pm);
}
}
/*
* Iterate PD locks to see what we can and cannot turn off.
*
* The argument to PRCMPowerDomainOff() is a bitwise OR, so every time
* we encounter a lock we just clear the respective bits in the 'domains'
* variable as required by the lock. In the end the domains variable will
* just hold whatever has not been cleared
*/
for(lock = list_head(power_domain_locks_list); lock != NULL;
lock = lock->next) {
/* Clear the bits specified in the lock */
domains &= ~lock->domains;
}
/* Pat the dog: We don't want it to shout right after we wake up */
watchdog_periodic();
/* Clear unacceptable bits, just in case a lock provided a bad value */
domains &= LOCKABLE_DOMAINS;
/*
* Freeze the IOs on the boundary between MCU and AON. We only do this if
* PERIPH is not needed
*/
if(domains & PRCM_DOMAIN_PERIPH) {
ti_lib_aon_ioc_freeze_enable();
}
/*
* Among LOCKABLE_DOMAINS, turn off those that are not locked
*
* If domains is != 0, pass it as-is
*/
if(domains) {
ti_lib_prcm_power_domain_off(domains);
}
/* Configure clock sources for MCU and AUX: No clock */
ti_lib_aon_wuc_mcu_power_down_config(AONWUC_NO_CLOCK);
ti_lib_aon_wuc_aux_power_down_config(AONWUC_NO_CLOCK);
/* Full RAM retention. */
ti_lib_aon_wuc_mcu_sram_config(MCU_RAM0_RETENTION | MCU_RAM1_RETENTION |
MCU_RAM2_RETENTION | MCU_RAM3_RETENTION);
/* Enable retention on the CPU domain */
ti_lib_prcm_retention_enable(PRCM_DOMAIN_CPU);
/* Disable retention of AUX RAM */
ti_lib_aon_wuc_aux_sram_config(false);
/* Disable retention in the RFCORE RAM */
HWREG(PRCM_BASE + PRCM_O_RAMRETEN) &= ~PRCM_RAMRETEN_RFC;
/* Disable retention of VIMS RAM (TRAM and CRAM) */
//TODO: This can probably be removed, we are calling ti_lib_prcm_retention_disable(PRCM_DOMAIN_VIMS); further down
HWREG(PRCM_BASE + PRCM_O_RAMRETEN) &= ~PRCM_RAMRETEN_VIMS_M;
/*
* Always turn off RFCORE, CPU, SYSBUS and VIMS. RFCORE should be off
* already
*/
ti_lib_prcm_power_domain_off(PRCM_DOMAIN_RFCORE | PRCM_DOMAIN_CPU |
PRCM_DOMAIN_VIMS | PRCM_DOMAIN_SYSBUS);
/* Request JTAG domain power off */
ti_lib_aon_wuc_jtag_power_off();
/* Turn off AUX */
ti_lib_aux_wuc_power_ctrl(AUX_WUC_POWER_OFF);
ti_lib_aon_wuc_domain_power_down_enable();
while(ti_lib_aon_wuc_power_status() & AONWUC_AUX_POWER_ON);
/* Configure the recharge controller */
ti_lib_sys_ctrl_set_recharge_before_power_down(false);
/*
* If both PERIPH and SERIAL PDs are off, request the uLDO for as the power
* source while in deep sleep.
*/
if(domains == LOCKABLE_DOMAINS) {
ti_lib_pwr_ctrl_source_set(PWRCTRL_PWRSRC_ULDO);
}
/* We are only interested in IRQ energest while idle or in LPM */
ENERGEST_IRQ_RESTORE(irq_energest);
ENERGEST_OFF(ENERGEST_TYPE_CPU);
ENERGEST_ON(ENERGEST_TYPE_LPM);
/* Sync the AON interface to ensure all writes have gone through. */
ti_lib_sys_ctrl_aon_sync();
/*
* Explicitly turn off VIMS cache, CRAM and TRAM. Needed because of
* retention mismatch between VIMS logic and cache. We wait to do this
* until right before deep sleep to be able to use the cache for as long
* as possible.
*/
ti_lib_prcm_retention_disable(PRCM_DOMAIN_VIMS);
ti_lib_vims_mode_set(VIMS_BASE, VIMS_MODE_OFF);
/* Deep Sleep */
ti_lib_prcm_deep_sleep();
/*
* When we reach here, some interrupt woke us up. The global interrupt
* flag is off, hence we have a chance to run things here. We will wake up
* the chip properly, and then we will enable the global interrupt without
* unpending events so the handlers can fire
*/
lpm_wake_up();
ti_lib_int_master_enable();
}
}
/*---------------------------------------------------------------------------*/
void
lpm_sleep(void)
{
ENERGEST_OFF(ENERGEST_TYPE_CPU);
ENERGEST_ON(ENERGEST_TYPE_LPM);
/* We are only interested in IRQ energest while idle or in LPM */
ENERGEST_IRQ_RESTORE(irq_energest);
/* Just to be on the safe side, explicitly disable Deep Sleep */
HWREG(NVIC_SYS_CTRL) &= ~(NVIC_SYS_CTRL_SLEEPDEEP);
ti_lib_prcm_sleep();
/* Remember IRQ energest for next pass */
ENERGEST_IRQ_SAVE(irq_energest);
ENERGEST_ON(ENERGEST_TYPE_CPU);
ENERGEST_OFF(ENERGEST_TYPE_LPM);
}
/*---------------------------------------------------------------------------*/
void
lpm_register_module(lpm_registered_module_t *module)
{
list_add(modules_list, module);
}
/*---------------------------------------------------------------------------*/
void
lpm_init()
{
list_init(modules_list);
list_init(power_domain_locks_list);
}
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
*/

172
cpu/cc26xx/lpm.h Normal file
View File

@ -0,0 +1,172 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup cc26xx
* @{
*
* \defgroup cc26xx-lpm CC26xx Low-Power management
*
* CC26xx low-power operation
*
* @{
*
* \file
* Header file for the management of CC26xx low-power operation
*/
/*---------------------------------------------------------------------------*/
#ifndef LPM_H_
#define LPM_H_
/*---------------------------------------------------------------------------*/
#include "pwr_ctrl.h"
#include <stdint.h>
/*---------------------------------------------------------------------------*/
#define LPM_MODE_SLEEP PWRCTRL_ACTIVE
#define LPM_MODE_DEEP_SLEEP PWRCTRL_POWER_DOWN
#define LPM_MODE_SHUTDOWN PWRCTRL_SHUTDOWN
#define LPM_MODE_MAX_SUPPORTED LPM_MODE_DEEP_SLEEP
/*---------------------------------------------------------------------------*/
typedef struct lpm_registered_module {
struct lpm_registered_module *next;
uint8_t (*request_max_pm)(void);
void (*shutdown)(uint8_t mode);
void (*wakeup)(void);
} lpm_registered_module_t;
/*---------------------------------------------------------------------------*/
/**
* \brief Declare a variable to be used in order to get notifications from LPM
* \param n the variable name to be declared
* \param m A pointer to a function which will tell the LPM module the max
* PM this module is willing to handle. This function will return
* LPM_MODE_SLEEP, LPM_MODE_DEEP_SLEEP etc. The LPM module will ask all
* registered modules and will trigger the highest LPM permitted
* \param s A pointer to a function which will receive a notification just
* before entering the low power mode. The callee can prepare for the
* imminent LPM state. The argument to this function will be the
* upcoming low power mode. This function can e.g. turn off a
* peripheral before the LPM module shuts down the power domain.
* \param w A pointer to a function which will be called just after we have
* woken up. This can be used to e.g. turn a peripheral back on. This
* function is in charge of turning power domains back on. This
* function will normally be called within an interrupt context.
*/
#define LPM_MODULE(n, m, s, w) static lpm_registered_module_t n = \
{ NULL, m, s, w }
/*---------------------------------------------------------------------------*/
/**
*
* \brief Data type used to control whether a PD will get shut down when the
* CM3 drops to deep sleep
*
* Modules using these facilities must allocate a variable of this type, but
* they must not try to manipulate it directly. Instead, the respective
* functions must be used
*
* \sa lpm_pd_lock_obtain(), lpm_pd_lock_release()
*/
typedef struct lpm_power_domain_lock {
struct lpm_power_domain_lock *next;
uint32_t domains;
} lpm_power_domain_lock_t;
/*---------------------------------------------------------------------------*/
/**
* \brief Prohibit a PD from turning off in standby mode
* \param lock A pointer to a lpm_power_domain_lock_t
* \param domains Bitwise OR from PRCM_DOMAIN_PERIPH, PRCM_DOMAIN_SERIAL
*
* The caller is responsible for allocating lpm_power_domain_lock_t
*
* Only the domains listed above can be locked / released, but a single lock
* can be used for multiple domains
*/
void lpm_pd_lock_obtain(lpm_power_domain_lock_t *lock, uint32_t domains);
/**
* \brief Permit a PD to turn off in standby mode
* \param pd A pointer to a previously used lock
*
* \sa lpm_pd_lock_obtain()
*/
void lpm_pd_lock_release(lpm_power_domain_lock_t *pd);
/**
* \brief Drop the cortex to sleep / deep sleep and shut down peripherals
*
* Whether the cortex will drop to sleep or deep sleep is configurable. The
* exact peripherals which will be shut down is also configurable
*/
void lpm_drop(void);
/**
* \brief Enter sleep mode
*/
void lpm_sleep(void);
/**
* \brief Put the chip in shutdown power mode
* \param wakeup_pin The GPIO pin which will wake us up. Must be IOID_0 etc...
*/
void lpm_shutdown(uint32_t wakeup_pin);
/**
* \brief Wake up from sleep mode
*
* This function must be called at the start of any interrupt context which
* may bring us out of sleep. Current interrupts do this already, but make sure
* to do the same when adding new ISRs
*/
void lpm_wake_up(void);
/**
* \brief Register a module for LPM notifications.
* \param module A pointer to the data structure with the module definition
*
* When the LPM module is about to drop to some low power mode, it will first
* notify all modules about this.
*
* This function must not be called before the module has been initialised
* with lpm_init(). The code does not perform checks: This is the caller's
* responsibility.
*/
void lpm_register_module(lpm_registered_module_t *module);
/**
* \brief Initialise the low-power mode management module
*/
void lpm_init(void);
/*---------------------------------------------------------------------------*/
#endif /* LPM_H_ */
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
*/

48
cpu/cc26xx/mtarch.h Normal file
View File

@ -0,0 +1,48 @@
/*
* Copyright (c) 2010, Loughborough University - Computer Science
* 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. The name of the author may not be used to endorse or promote
* products derived from this software without specific prior
* written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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.
*
*/
/*
* \file
* Stub header file for multi-threading. It doesn't do anything, it
* just exists so that mt.c can compile cleanly.
*
* This is based on the original mtarch.h for z80 by Takahide Matsutsuka
*
* \author
* George Oikonomou - <oikonomou@users.sourceforge.net>
*/
#ifndef __MTARCH_H__
#define __MTARCH_H__
struct mtarch_thread {
unsigned char *sp;
};
#endif /* __MTARCH_H__ */

70
cpu/cc26xx/putchar.c Normal file
View File

@ -0,0 +1,70 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
#include "cc26xx-uart.h"
#include <string.h>
/*---------------------------------------------------------------------------*/
int
putchar(int c)
{
cc26xx_uart_write_byte(c);
return c;
}
/*---------------------------------------------------------------------------*/
int
puts(const char *str)
{
int i;
if(str == NULL) {
return 0;
}
for(i = 0; i < strlen(str); i++) {
putchar(str[i]);
}
putchar('\n');
return i;
}
/*---------------------------------------------------------------------------*/
unsigned int
dbg_send_bytes(const unsigned char *s, unsigned int len)
{
unsigned int i = 0;
while(s && *s != 0) {
if(i >= len) {
break;
}
putchar(*s++);
i++;
}
return i;
}
/*---------------------------------------------------------------------------*/

92
cpu/cc26xx/rtimer-arch.c Normal file
View File

@ -0,0 +1,92 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup cc26xx-rtimer
* @{
*
* \file
* Implementation of the arch-specific rtimer functions for the cc26xx
*
*/
/*---------------------------------------------------------------------------*/
#include "contiki.h"
#include "sys/energest.h"
#include "sys/rtimer.h"
#include "cpu.h"
#include "dev/cc26xx-rtc.h"
#include "ti-lib.h"
#include <stdint.h>
/*---------------------------------------------------------------------------*/
/**
* \brief We don't need to do anything special here. The RTC is initialised
* elsewhere
*/
void
rtimer_arch_init(void)
{
return;
}
/*---------------------------------------------------------------------------*/
/**
* \brief Schedules an rtimer task to be triggered at time t
* \param t The time when the task will need executed.
*
* \e t is an absolute time, in other words the task will be executed AT
* time \e t, not IN \e t rtimer ticks.
*
* This function schedules a one-shot event with the AON RTC.
*
* This functions converts \e to a value suitable for the AON RTC.
*/
void
rtimer_arch_schedule(rtimer_clock_t t)
{
/* Convert the rtimer tick value to a value suitable for the AON RTC */
cc26xx_rtc_schedule_one_shot(t);
}
/*---------------------------------------------------------------------------*/
/**
* \brief Returns the current real-time clock time
* \return The current rtimer time in ticks
*
* The value is read from the AON RTC counter and converted to a number of
* rtimer ticks
*
*/
rtimer_clock_t
rtimer_arch_now()
{
return ti_lib_aon_rtc_current_compare_value_get();
}
/*---------------------------------------------------------------------------*/
/** @} */

65
cpu/cc26xx/rtimer-arch.h Normal file
View File

@ -0,0 +1,65 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup cc26xx-clocks
* @{
*
* \defgroup cc26xx-rtimer CC26xx rtimer
*
* Implementation of the rtimer module for the CC26xx
*
* The rtimer runs on the AON RTC. We set the RTC's channel 2 to continuous
* compare mode, instead of scheduling the next tick interrupt by software.
* This gives us completely equidistant events.
*
* The RTC runs in all power modes (except shutdown)
* @{
*/
/**
* \file
* Header file for the CC26xx rtimer driver
*/
/*---------------------------------------------------------------------------*/
#ifndef RTIMER_ARCH_H_
#define RTIMER_ARCH_H_
/*---------------------------------------------------------------------------*/
#include "contiki.h"
/*---------------------------------------------------------------------------*/
#define RTIMER_ARCH_SECOND 65536
/*---------------------------------------------------------------------------*/
rtimer_clock_t rtimer_arch_now(void);
/*---------------------------------------------------------------------------*/
#endif /* RTIMER_ARCH_H_ */
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
*/

65
cpu/cc26xx/slip-arch.c Normal file
View File

@ -0,0 +1,65 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup cc26xx-char-io
* @{
*
* \file
* Arch-specific SLIP functions for the cc26xx
*/
/*---------------------------------------------------------------------------*/
#include "contiki-conf.h"
#include "dev/cc26xx-uart.h"
#include "dev/slip.h"
/*---------------------------------------------------------------------------*/
/**
* \brief Write a byte over SLIP
* \param c the byte
*/
void
slip_arch_writeb(unsigned char c)
{
cc26xx_uart_write_byte(c);
}
/*---------------------------------------------------------------------------*/
/**
* \brief Initialise the arch-specific SLIP driver
* \param ubr Ignored for the cc26xx
*/
void
slip_arch_init(unsigned long ubr)
{
cc26xx_uart_set_input(slip_input_byte);
}
/*---------------------------------------------------------------------------*/
/** @} */

667
cpu/cc26xx/ti-lib.h Normal file
View File

@ -0,0 +1,667 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/**
* \addtogroup cc26xx
* @{
*
* \defgroup cc26xx-ti-lib TI CC26xxware Glue
*
* Glue file which renames TI CC26xxware functions. Thus, for example,
* PowerCtrlIOFreezeDisable() becomes power_ctrl_io_freeze_disable()
*
* This is not strictly required and a call to the former will work perfectly
* correctly. However, in using those macros, we make the core of the Contiki
* port match the naming convention.
*
* Since all functions are prefixed with ti_lib, it also becomes clear to the
* reader that this is a call to TI driverlib's sources and not a call to a
* function inside Contiki
*
* @{
*
* \file
* Header file with macros which rename TI CC26xxware functions.
*/
#ifndef TI_LIB_H_
#define TI_LIB_H_
/*---------------------------------------------------------------------------*/
/* aon_batmon.h */
#include "driverlib/aon_batmon.h"
#define ti_lib_aon_batmon_enable(...) AONBatMonEnable(__VA_ARGS__)
#define ti_lib_aon_batmon_disable(...) AONBatMonDisable(__VA_ARGS__)
#define ti_lib_aon_batmon_measurement_cycle_set(...) AONBatMonMeasurementCycleSet(__VA_ARGS__)
#define ti_lib_aon_batmon_measurement_cycle_get(...) AONBatMonMeasurementCycleGet(__VA_ARGS__)
#define ti_lib_aon_batmon_battery_trim_set(...) AONBatMonBatteryTrimSet(__VA_ARGS__)
#define ti_lib_aon_batmon_temperature_trim_set(...) AONBatMonTemperatureTrimSet(__VA_ARGS__)
#define ti_lib_aon_batmon_temperature_get(...) AONBatMonTemperatureGet(__VA_ARGS__)
#define ti_lib_aon_batmon_temp_get_deg(...) AON_BatmonTempGetDegC(__VA_ARGS__)
#define ti_lib_aon_batmon_battery_voltage_get(...) AONBatMonBatteryVoltageGet(__VA_ARGS__)
#define ti_lib_aon_batmon_new_battery_measure_ready(...) AONBatMonNewBatteryMeasureReady(__VA_ARGS__)
#define ti_lib_aon_batmon_new_temp_measure_ready(...) AONBatMonNewTempMeasureReady(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* aon_event.h */
#include "driverlib/aon_event.h"
#define ti_lib_aon_event_mcu_wake_up_set(...) AONEventMcuWakeUpSet(__VA_ARGS__)
#define ti_lib_aon_event_mcu_wake_up_get(...) AONEventMcuWakeUpGet(__VA_ARGS__)
#define ti_lib_aon_event_aux_wake_up_set(...) AONEventAuxWakeUpSet(__VA_ARGS__)
#define ti_lib_aon_event_aux_wake_up_get(...) AONEventAuxWakeUpGet(__VA_ARGS__)
#define ti_lib_aon_event_mcu_set(...) AONEventMcuSet(__VA_ARGS__)
#define ti_lib_aon_event_mcu_get(...) AONEventMcuGet(__VA_ARGS__)
#define ti_lib_aon_event_rtc_set(...) AONEventRtcSet(__VA_ARGS__)
#define ti_lib_aon_event_rtc_get(...) AONEventRtcGet(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* aon_ioc.h */
#include "driverlib/aon_ioc.h"
#define ti_lib_aon_ioc_drive_strength_set(...) AONIOCDriveStrengthSet(__VA_ARGS__)
#define ti_lib_aon_ioc_drive_strength_get(...) AONIOCDriveStrengthGet(__VA_ARGS__)
#define ti_lib_aon_ioc_freeze_enable(...) AONIOCFreezeEnable(__VA_ARGS__)
#define ti_lib_aon_ioc_freeze_disable(...) AONIOCFreezeDisable(__VA_ARGS__)
#define ti_lib_aon_ioc_32_khz_output_disable(...) AONIOC32kHzOutputDisable(__VA_ARGS__)
#define ti_lib_aon_ioc_32_khz_output_enable(...) AONIOC32kHzOutputEnable(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* aon_rtc.h */
#include "driverlib/aon_rtc.h"
#define ti_lib_aon_rtc_enable(...) AONRTCEnable(__VA_ARGS__)
#define ti_lib_aon_rtc_disable(...) AONRTCDisable(__VA_ARGS__)
#define ti_lib_aon_rtc_status(...) AONRTCStatus(__VA_ARGS__)
#define ti_lib_aon_rtc_reset(...) AONRTCReset(__VA_ARGS__)
#define ti_lib_aon_rtc_delay_config(...) AONRTCDelayConfig(__VA_ARGS__)
#define ti_lib_aon_rtc_combined_event_config(...) AONRTCCombinedEventConfig(__VA_ARGS__)
#define ti_lib_aon_rtc_event_clear(...) AONRTCEventClear(__VA_ARGS__)
#define ti_lib_aon_rtc_event_get(...) AONRTCEventGet(__VA_ARGS__)
#define ti_lib_aon_rtc_sec_get(...) AONRTCSecGet(__VA_ARGS__)
#define ti_lib_aon_rtc_fraction_get(...) AONRTCFractionGet(__VA_ARGS__)
#define ti_lib_aon_rtc_sub_sec_incr_get(...) AONRTCSubSecIncrGet(__VA_ARGS__)
#define ti_lib_aon_rtc_mode_ch1_set(...) AONRTCModeCh1Set(__VA_ARGS__)
#define ti_lib_aon_rtc_mode_ch1_get(...) AONRTCModeCh1Get(__VA_ARGS__)
#define ti_lib_aon_rtc_mode_ch2_set(...) AONRTCModeCh2Set(__VA_ARGS__)
#define ti_lib_aon_rtc_mode_ch2_get(...) AONRTCModeCh2Get(__VA_ARGS__)
#define ti_lib_aon_rtc_channel_enable(...) AONRTCChannelEnable(__VA_ARGS__)
#define ti_lib_aon_rtc_channel_disable(...) AONRTCChannelDisable(__VA_ARGS__)
#define ti_lib_aon_rtc_compare_value_set(...) AONRTCCompareValueSet(__VA_ARGS__)
#define ti_lib_aon_rtc_compare_value_get(...) AONRTCCompareValueGet(__VA_ARGS__)
#define ti_lib_aon_rtc_current_compare_value_get(...) AONRTCCurrentCompareValueGet(__VA_ARGS__)
#define ti_lib_aon_rtc_inc_value_ch2_set(...) AONRTCIncValueCh2Set(__VA_ARGS__)
#define ti_lib_aon_rtc_inc_value_ch2_get(...) AONRTCIncValueCh2Get(__VA_ARGS__)
#define ti_lib_aon_rtc_capture_value_ch1_get(...) AONRTCCaptureValueCh1Get(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* aon_wuc.h */
#include "driverlib/aon_wuc.h"
#define ti_lib_aon_wuc_mcu_wake_up_config(...) AONWUCMcuWakeUpConfig(__VA_ARGS__)
#define ti_lib_aon_wuc_mcu_power_down_config(...) AONWUCMcuPowerDownConfig(__VA_ARGS__)
#define ti_lib_aon_wuc_mcu_power_off_config(...) AONWUCMcuPowerOffConfig(__VA_ARGS__)
#define ti_lib_aon_wuc_mcu_sram_config(...) AONWUCMcuSRamConfig(__VA_ARGS__)
#define ti_lib_aon_wuc_aux_clock_config_set(...) AONWUCAuxClockConfigSet(__VA_ARGS__)
#define ti_lib_aon_wuc_aux_clock_config_get(...) AONWUCAuxClockConfigGet(__VA_ARGS__)
#define ti_lib_aon_wuc_aux_power_down_config(...) AONWUCAuxPowerDownConfig(__VA_ARGS__)
#define ti_lib_aon_wuc_aux_power_off_config(...) AONWUCAuxPowerOffConfig(__VA_ARGS__)
#define ti_lib_aon_wuc_aux_wake_up_config(...) AONWUCAuxWakeUpConfig(__VA_ARGS__)
#define ti_lib_aon_wuc_aux_sram_config(...) AONWUCAuxSRamConfig(__VA_ARGS__)
#define ti_lib_aon_wuc_aux_wakeup_event(...) AONWUCAuxWakeupEvent(__VA_ARGS__)
#define ti_lib_aon_wuc_aux_image_valid(...) AONWUCAuxImageValid(__VA_ARGS__)
#define ti_lib_aon_wuc_aux_image_invalid(...) AONWUCAuxImageInvalid(__VA_ARGS__)
#define ti_lib_aon_wuc_aux_reset(...) AONWUCAuxReset(__VA_ARGS__)
#define ti_lib_aon_wuc_power_status(...) AONWUCPowerStatus(__VA_ARGS__)
#define ti_lib_aon_wuc_shut_down_enable(...) AONWUCShutDownEnable(__VA_ARGS__)
#define ti_lib_aon_wuc_domain_power_down_enable(...) AONWUCDomainPowerDownEnable(__VA_ARGS__)
#define ti_lib_aon_wuc_domain_power_down_disable(...) AONWUCDomainPowerDownDisable(__VA_ARGS__)
#define ti_lib_aon_wuc_mcu_reset_status(...) AONWUCMcuResetStatus(__VA_ARGS__)
#define ti_lib_aon_wuc_mcu_reset_clear(...) AONWUCMcuResetClear(__VA_ARGS__)
#define ti_lib_aon_wuc_recharge_ctrl_config_set(...) AONWUCRechargeCtrlConfigSet(__VA_ARGS__)
#define ti_lib_aon_wuc_recharge_ctrl_config_get(...) AONWUCRechargeCtrlConfigGet(__VA_ARGS__)
#define ti_lib_aon_wuc_osc_config(...) AONWUCOscConfig(__VA_ARGS__)
#define ti_lib_aon_wuc_jtag_power_off(...) AONWUCJtagPowerOff(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* aux_wuc.h */
#include "driverlib/aux_wuc.h"
#define ti_lib_aux_wuc_clock_enable(...) AUXWUCClockEnable(__VA_ARGS__)
#define ti_lib_aux_wuc_clock_disble(...) AUXWUCClockDisable(__VA_ARGS__)
#define ti_lib_aux_wuc_clock_status(...) AUXWUCClockStatus(__VA_ARGS__)
#define ti_lib_aux_wuc_clock_freq_req(...) AUXWUCClockFreqReq(__VA_ARGS__)
#define ti_lib_aux_wuc_power_ctrl(...) AUXWUCPowerCtrl(__VA_ARGS__)
#define ti_lib_aux_wuc_freeze_enable(...) AUXWUCFreezeEnable(__VA_ARGS__)
#define ti_lib_aux_wuc_freeze_disable(...) AUXWUCFreezeDisable(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* cpu.h */
#include "driverlib/cpu.h"
#define ti_lib_cpu_cpsid(...) CPUcpsid(__VA_ARGS__)
#define ti_lib_cpu_cpsie(...) CPUcpsie(__VA_ARGS__)
#define ti_lib_cpu_primask(...) CPUprimask(__VA_ARGS__)
#define ti_lib_cpu_wfi(...) CPUwfi(__VA_ARGS__)
#define ti_lib_cpu_wfe(...) CPUwfe(__VA_ARGS__)
#define ti_lib_cpu_sev(...) CPUsev(__VA_ARGS__)
#define ti_lib_cpu_base_pri_get(...) CPUbasepriGet(__VA_ARGS__)
#define ti_lib_cpu_base_pri_set(...) CPUbasepriSet(__VA_ARGS__)
#define ti_lib_cpu_delay(...) CPUdelay(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* ddi.h */
#include "driverlib/ddi.h"
#define ti_lib_aux_adi_ddi_safe_write(...) AuxAdiDdiSafeWrite(__VA_ARGS__)
#define ti_lib_aux_adi_ddi_safe_read(...) AuxAdiDdiSafeRead(__VA_ARGS__)
#define ti_lib_ddi_status_get(...) DDIStatusGet(__VA_ARGS__)
#define ti_lib_ddi_config_set(...) DDIConfigSet(__VA_ARGS__)
#define ti_lib_ddi_sync(...) DDISync(__VA_ARGS__)
#define ti_lib_ddi_protect(...) DDIProtect(__VA_ARGS__)
#define ti_lib_ddi_32_reg_write(...) DDI32RegWrite(__VA_ARGS__)
#define ti_lib_ddi_32_reg_read(...) DDI32RegRead(__VA_ARGS__)
#define ti_lib_ddi_32_bits_set(...) DDI32BitsSet(__VA_ARGS__)
#define ti_lib_ddi_32_bits_clear(...) DDI32BitsClear(__VA_ARGS__)
#define ti_lib_ddi_8_set_val_bit(...) DDI8SetValBit(__VA_ARGS__)
#define ti_lib_ddi_16_set_val_bit(...) DDI16SetValBit(__VA_ARGS__)
#define ti_lib_ddi_16_bit_write(...) DDI16BitWrite(__VA_ARGS__)
#define ti_lib_ddi_16_bit_field_write(...) DDI16BitfieldWrite(__VA_ARGS__)
#define ti_lib_ddi_16_bit_read(...) DDI16BitRead(__VA_ARGS__)
#define ti_lib_ddi_16_bitfield_read(...) DDI16BitfieldRead(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* gpio.h */
#include "driverlib/gpio.h"
#define ti_lib_gpio_dir_mode_set(...) GPIODirModeSet(__VA_ARGS__)
#define ti_lib_gpio_dir_mode_get(...) GPIODirModeGet(__VA_ARGS__)
#define ti_lib_gpio_pin_write(...) GPIOPinWrite(__VA_ARGS__)
#define ti_lib_gpio_pin_read(...) GPIOPinRead(__VA_ARGS__)
#define ti_lib_gpio_pin_clear(...) GPIOPinClear(__VA_ARGS__)
#define ti_lib_gpio_pin_toggle(...) GPIOPinToggle(__VA_ARGS__)
#define ti_lib_gpio_event_get(...) GPIOEventGet(__VA_ARGS__)
#define ti_lib_gpio_event_clear(...) GPIOEventClear(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* i2c.h */
#include "driverlib/i2c.h"
#define ti_lib_i2c_int_register(...) I2CIntRegister(__VA_ARGS__)
#define ti_lib_i2c_int_unregister(...) I2CIntUnregister(__VA_ARGS__)
#define ti_lib_i2c_master_bus_busy(...) I2CMasterBusBusy(__VA_ARGS__)
#define ti_lib_i2c_master_busy(...) I2CMasterBusy(__VA_ARGS__)
#define ti_lib_i2c_master_control(...) I2CMasterControl(__VA_ARGS__)
#define ti_lib_i2c_master_data_get(...) I2CMasterDataGet(__VA_ARGS__)
#define ti_lib_i2c_master_data_put(...) I2CMasterDataPut(__VA_ARGS__)
#define ti_lib_i2c_master_disable(...) I2CMasterDisable(__VA_ARGS__)
#define ti_lib_i2c_master_enable(...) I2CMasterEnable(__VA_ARGS__)
#define ti_lib_i2c_master_err(...) I2CMasterErr(__VA_ARGS__)
#define ti_lib_i2c_master_init_exp_clk(...) I2CMasterInitExpClk(__VA_ARGS__)
#define ti_lib_i2c_master_int_clear(...) I2CMasterIntClear(__VA_ARGS__)
#define ti_lib_i2c_master_int_disable(...) I2CMasterIntDisable(__VA_ARGS__)
#define ti_lib_i2c_master_int_enable(...) I2CMasterIntEnable(__VA_ARGS__)
#define ti_lib_i2c_master_int_status(...) I2CMasterIntStatus(__VA_ARGS__)
#define ti_lib_i2c_master_slave_addr_set(...) I2CMasterSlaveAddrSet(__VA_ARGS__)
#define ti_lib_i2c_slave_data_get(...) I2CSlaveDataGet(__VA_ARGS__)
#define ti_lib_i2c_slave_data_put(...) I2CSlaveDataPut(__VA_ARGS__)
#define ti_lib_i2c_slave_disable(...) I2CSlaveDisable(__VA_ARGS__)
#define ti_lib_i2c_slave_enable(...) I2CSlaveEnable(__VA_ARGS__)
#define ti_lib_i2c_slave_init(...) I2CSlaveInit(__VA_ARGS__)
#define ti_lib_i2c_slave_address_set(...) I2CSlaveAddressSet(__VA_ARGS__)
#define ti_lib_i2c_slave_int_clear(...) I2CSlaveIntClear(__VA_ARGS__)
#define ti_lib_i2c_slave_int_disable(...) I2CSlaveIntDisable(__VA_ARGS__)
#define ti_lib_i2c_slave_int_enable(...) I2CSlaveIntEnable(__VA_ARGS__)
#define ti_lib_i2c_slave_int_status(...) I2CSlaveIntStatus(__VA_ARGS__)
#define ti_lib_i2c_slave_status(...) I2CSlaveStatus(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* interrupt.h */
#include "driverlib/interrupt.h"
#define ti_lib_int_master_enable(...) IntMasterEnable(__VA_ARGS__)
#define ti_lib_int_master_disable(...) IntMasterDisable(__VA_ARGS__)
#define ti_lib_int_register(...) IntRegister(__VA_ARGS__);
#define ti_lib_int_unregsiter(...) IntUnregister(__VA_ARGS__)
#define ti_lib_int_priority_grouping_set(...) IntPriorityGroupingSet(__VA_ARGS__)
#define ti_lib_int_priority_grouping_get(...) IntPriorityGroupingGet(__VA_ARGS__)
#define ti_lib_int_priority_set(...) IntPrioritySet(__VA_ARGS__)
#define ti_lib_int_priority_get(...) IntPriorityGet(__VA_ARGS__)
#define ti_lib_int_enable(...) IntEnable(__VA_ARGS__)
#define ti_lib_int_disable(...) IntDisable(__VA_ARGS__)
#define ti_lib_int_pend_set(...) IntPendSet(__VA_ARGS__)
#define ti_lib_int_pend_get(...) IntPendGet(__VA_ARGS__)
#define ti_lib_int_pend_clear(...) IntPendClear(__VA_ARGS__)
#define ti_lib_int_mask_set(...) IntPriorityMaskSet(__VA_ARGS__)
#define ti_lib_int_mask_get(...) IntPriorityMaskGet(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* ioc.h */
#include "driverlib/ioc.h"
#define ti_lib_ioc_port_configure_set(...) IOCPortConfigureSet(__VA_ARGS__)
#define ti_lib_ioc_port_configure_get(...) IOCPortConfigureGet(__VA_ARGS__)
#define ti_lib_ioc_io_shutdown_set(...) IOCIOShutdownSet(__VA_ARGS__)
#define ti_lib_ioc_io_jtag_set(...) IOCIOJTagSet(__VA_ARGS__)
#define ti_lib_ioc_io_mode_set(...) IOCIOModeSet(__VA_ARGS__)
#define ti_lib_ioc_io_port_pull_set(...) IOCIOPortPullSet(__VA_ARGS__)
#define ti_lib_ioc_io_hyst_set(...) IOCIOHystSet(__VA_ARGS__)
#define ti_lib_ioc_io_input_set(...) IOCIOInputSet(__VA_ARGS__)
#define ti_lib_ioc_io_slew_ctrl_set(...) IOCIOSlewCtrlSet(__VA_ARGS__)
#define ti_lib_ioc_io_drv_strength_set(...) IOCIODrvStrengthSet(__VA_ARGS__)
#define ti_lib_ioc_io_port_id_set(...) IOCIOPortIdSet(__VA_ARGS__)
#define ti_lib_ioc_io_int_set(...) IOCIOIntSet(__VA_ARGS__)
#define ti_lib_ioc_int_register(...) IOCIntRegister(__VA_ARGS__);
#define ti_lib_ioc_int_unregister(...) IOCIntUnregister(__VA_ARGS__)
#define ti_lib_ioc_int_enable(...) IOCIntEnable(__VA_ARGS__)
#define ti_lib_ioc_int_disable(...) IOCIntDisable(__VA_ARGS__)
#define ti_lib_ioc_int_clear(...) IOCIntClear(__VA_ARGS__)
#define ti_lib_ioc_int_status(...) IOCIntStatus(__VA_ARGS__)
#define ti_lib_ioc_pin_type_gpio_input(...) IOCPinTypeGpioInput(__VA_ARGS__)
#define ti_lib_ioc_pin_type_gpio_output(...) IOCPinTypeGpioOutput(__VA_ARGS__)
#define ti_lib_ioc_pin_type_uart(...) IOCPinTypeUart(__VA_ARGS__)
#define ti_lib_ioc_pin_type_ssi_master(...) IOCPinTypeSsiMaster(__VA_ARGS__)
#define ti_lib_ioc_pin_type_ssi_slave(...) IOCPinTypeSsiSlave(__VA_ARGS__)
#define ti_lib_ioc_pin_type_i2c(...) IOCPinTypeI2c(__VA_ARGS__)
#define ti_lib_ioc_pin_type_aux(...) IOCPinTypeAux(__VA_ARGS__)
#define ti_lib_ioc_pin_type_spis(...) IOCPinTypeSpis(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* osc.h */
#include "driverlib/osc.h"
#define ti_lib_osc_xhf_power_mode_set(...) OSCXHfPowerModeSet(__VA_ARGS__)
#define ti_lib_osc_clock_source_set(...) OSCClockSourceSet(__VA_ARGS__)
#define ti_lib_osc_clock_source_get(...) OSCClockSourceGet(__VA_ARGS__)
#define ti_lib_osc_hf_source_ready(...) OSCHfSourceReady(__VA_ARGS__)
#define ti_lib_osc_hf_source_switch(...) OSCHfSourceSwitch(__VA_ARGS__)
#define ti_lib_osc_interface_enable(...) OSCInterfaceEnable(__VA_ARGS__)
#define ti_lib_osc_interface_disable(...) OSCInterfaceDisable(__VA_ARGS__)
#define ti_lib_osc_hf_get_startup_time(...) OSCHF_GetStartupTime(__VA_ARGS__)
#define ti_lib_osc_hf_turn_on_xosc(...) OSCHF_TurnOnXosc(__VA_ARGS__)
#define ti_lib_osc_hf_attempt_to_switch_to_xosc(...) OSCHF_AttemptToSwitchToXosc(__VA_ARGS__)
#define ti_lib_osc_hf_switch_to_rc_osc_turn_off_xosc(...) OSCHF_SwitchToRcOscTurnOffXosc(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* prcm.h */
#include "driverlib/prcm.h"
#define ti_lib_prcm_inf_clock_configure_set(...) PRCMInfClockConfigureSet(__VA_ARGS__)
#define ti_lib_prcm_inf_clock_configure_get(...) PRCMInfClockConfigureGet(__VA_ARGS__)
#define ti_lib_prcm_mcu_power_off(...) PRCMMcuPowerOff(__VA_ARGS__)
#define ti_lib_prcm_mcu_power_off_cancel(...) PRCMMcuPowerOffCancel(__VA_ARGS__)
#define ti_lib_prcm_mcu_uldo_configure(...) PRCMMcuUldoConfigure(__VA_ARGS__)
#define ti_lib_prcm_clock_configure_set(...) PRCMClockConfigureSet(__VA_ARGS__)
#define ti_lib_prcm_clock_configure_get(...) PRCMClockConfigureGet(__VA_ARGS__)
#define ti_lib_prcm_audio_clock_enable(...) PRCMAudioClockEnable(__VA_ARGS__)
#define ti_lib_prcm_audio_clock_disable(...) PRCMAudioClockDisable(__VA_ARGS__)
#define ti_lib_prcm_audio_clock_config_set(...) PRCMAudioClockConfigSet(__VA_ARGS__)
#define ti_lib_prcm_load_set(...) PRCMLoadSet(__VA_ARGS__)
#define ti_lib_prcm_load_get(...) PRCMLoadGet(__VA_ARGS__)
#define ti_lib_prcm_domain_enable(...) PRCMDomainEnable(__VA_ARGS__)
#define ti_lib_prcm_domain_disable(...) PRCMDomainDisable(__VA_ARGS__)
#define ti_lib_prcm_power_domain_on(...) PRCMPowerDomainOn(__VA_ARGS__)
#define ti_lib_prcm_power_domain_off(...) PRCMPowerDomainOff(__VA_ARGS__)
#define ti_lib_prcm_rf_power_down_when_idle(...) PRCMRfPowerDownWhenIdle(__VA_ARGS__)
#define ti_lib_prcm_peripheral_run_enable(...) PRCMPeripheralRunEnable(__VA_ARGS__)
#define ti_lib_prcm_peripheral_run_disable(...) PRCMPeripheralRunDisable(__VA_ARGS__)
#define ti_lib_prcm_peripheral_sleep_enable(...) PRCMPeripheralSleepEnable(__VA_ARGS__)
#define ti_lib_prcm_peripheral_sleep_disable(...) PRCMPeripheralSleepDisable(__VA_ARGS__)
#define ti_lib_prcm_peripheral_deep_sleep_enable(...) PRCMPeripheralDeepSleepEnable(__VA_ARGS__)
#define ti_lib_prcm_peripheral_deep_sleep_disable(...) PRCMPeripheralDeepSleepDisable(__VA_ARGS__)
#define ti_lib_prcm_power_domain_status(...) PRCMPowerDomainStatus(__VA_ARGS__)
#define ti_lib_prcm_rf_ready(...) PRCMRfReady(__VA_ARGS__)
#define ti_lib_prcm_wdt_reset_status(...) PRCMWdtResetStatus(__VA_ARGS__)
#define ti_lib_prcm_sleep(...) PRCMSleep(__VA_ARGS__)
#define ti_lib_prcm_deep_sleep(...) PRCMDeepSleep(__VA_ARGS__)
#define ti_lib_prcm_retention_enable(...) PRCMRetentionEnable(__VA_ARGS__)
#define ti_lib_prcm_retention_disable(...) PRCMRetentionDisable(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* sys_ctrl.h */
#include "driverlib/pwr_ctrl.h"
#define ti_lib_pwr_ctrl_state_set(...) PowerCtrlStateSet(__VA_ARGS__)
#define ti_lib_pwr_ctrl_source_set(...) PowerCtrlSourceSet(__VA_ARGS__)
#define ti_lib_pwr_ctrl_source_get(...) PowerCtrlSourceGet(__VA_ARGS__)
#define ti_lib_pwr_ctrl_io_config_set(...) PowerCtrlIoConfigSet(__VA_ARGS__)
#define ti_lib_pwr_ctrl_reset_source_get(...) PowerCtrlResetSourceGet(__VA_ARGS__)
#define ti_lib_pwr_ctrl_reset_source_clear(...) PowerCtrlResetSourceClear(__VA_ARGS__)
#define ti_lib_pwr_ctrl_io_freeze_enable(...) PowerCtrlIOFreezeEnable(__VA_ARGS__)
#define ti_lib_pwr_ctrl_io_freeze_disable(...) PowerCtrlIOFreezeDisable(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* 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_IOC API */
#define ti_lib_rom_aon_ioc_drive_strength_set ROM_AONIOCDriveStrengthSet
#define ti_lib_rom_aon_ioc_drive_strength_get ROM_AONIOCDriveStrengthGet
/* AON_RTC API */
#define ti_lib_rom_aon_rtc_status ROM_AONRTCStatus
#define ti_lib_rom_aon_rtc_event_clear ROM_AONRTCEventClear
#define ti_lib_rom_aon_rtc_event_get ROM_AONRTCEventGet
#define ti_lib_rom_aon_rtc_mode_ch1_set ROM_AONRTCModeCh1Set
#define ti_lib_rom_aon_rtc_mode_ch1_get ROM_AONRTCModeCh1Get
#define ti_lib_rom_aon_rtc_mode_ch2_set ROM_AONRTCModeCh2Set
#define ti_lib_rom_aon_rtc_mode_ch2_get ROM_AONRTCModeCh2Get
#define ti_lib_rom_aon_rtc_channel_enable ROM_AONRTCChannelEnable
#define ti_lib_rom_aon_rtc_channel_disable ROM_AONRTCChannelDisable
#define ti_lib_rom_aon_rtc_compare_value_set ROM_AONRTCCompareValueSet
#define ti_lib_rom_aon_rtc_compare_value_get ROM_AONRTCCompareValueGet
#define ti_lib_rom_aon_rtc_current_compare_value_get ROM_AONRTCCurrentCompareValueGet
/* AON_WUC API */
#define ti_lib_rom_aon_wuc_aux_clock_config_set ROM_AONWUCAuxClockConfigSet
#define ti_lib_rom_aon_wuc_aux_s_ram_config ROM_AONWUCAuxSRamConfig
#define ti_lib_rom_aon_wuc_aux_wakeup_event ROM_AONWUCAuxWakeupEvent
#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_TIMER API */
#define ti_lib_rom_aux_timer_configure ROM_AUXTimerConfigure
#define ti_lib_rom_aux_timer_start ROM_AUXTimerStart
#define ti_lib_rom_aux_timer_stop ROM_AUXTimerStop
#define ti_lib_rom_aux_timer_prescale_set ROM_AUXTimerPrescaleSet
#define ti_lib_rom_aux_timer_prescale_get ROM_AUXTimerPrescaleGet
/* 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_sector_erase ROM_FlashSectorErase
#define ti_lib_rom_flash_program ROM_FlashProgram
#define ti_lib_rom_flash_program_nowait ROM_FlashProgramNowait
#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
#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_jtag_set ROM_IOCIOJTagSet
#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_spis ROM_IOCPinTypeSpis
#define ti_lib_rom_ioc_pin_type_aux ROM_IOCPinTypeAux
/* 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_clock_configure_set ROM_PRCMClockConfigureSet
#define ti_lib_rom_prcm_clock_configure_get ROM_PRCMClockConfigureGet
#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
#define ti_lib_rom_prcm_retention_enable ROM_PRCMRetentionEnable
#define ti_lib_rom_prcm_retention_disable ROM_PRCMRetentionDisable
/* SMPH API */
#define ti_lib_rom_smph_acquire ROM_SMPHAcquire
/* SPIS API */
#define ti_lib_rom_spis_data_put ROM_SPISDataPut
#define ti_lib_rom_spis_tx_get_value ROM_SPISTxGetValue
#define ti_lib_rom_spis_data_get ROM_SPISDataGet
#define ti_lib_rom_spis_rx_get_value ROM_SPISRxGetValue
#define ti_lib_rom_spis_int_status ROM_SPISIntStatus
/* 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_trigger_control ROM_TimerTriggerControl
#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_configure ROM_TRNGConfigure
#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
#define ti_lib_rom_vims_mode_get ROM_VIMSModeGet
/*---------------------------------------------------------------------------*/
/* sys_ctrl.h */
#include "driverlib/sys_ctrl.h"
#define ti_lib_sys_ctrl_power_everything(...) SysCtrlPowerEverything(__VA_ARGS__)
#define ti_lib_sys_ctrl_powerdown(...) SysCtrlPowerdown(__VA_ARGS__)
#define ti_lib_sys_ctrl_standby(...) SysCtrlStandby(__VA_ARGS__)
#define ti_lib_sys_ctrl_shutdown(...) SysCtrlShutdown(__VA_ARGS__)
#define ti_lib_sys_ctrl_clock_get(...) SysCtrlClockGet(__VA_ARGS__)
#define ti_lib_sys_ctrl_peripheral_clock_get(...) SysCtrlPeripheralClockGet(__VA_ARGS__)
#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__)
/*---------------------------------------------------------------------------*/
/* ssi.h */
#include "driverlib/ssi.h"
#define ti_lib_ssi_config_set_exp_clk(...) SSIConfigSetExpClk(__VA_ARGS__)
#define ti_lib_ssi_enable(...) SSIEnable(__VA_ARGS__)
#define ti_lib_ssi_disable(...) SSIDisable(__VA_ARGS__)
#define ti_lib_ssi_data_put(...) SSIDataPut(__VA_ARGS__)
#define ti_lib_ssi_data_put_non_blocking(...) SSIDataPutNonBlocking(__VA_ARGS__)
#define ti_lib_ssi_data_get(...) SSIDataGet(__VA_ARGS__)
#define ti_lib_ssi_data_get_non_blocking(...) SSIDataGetNonBlocking(__VA_ARGS__)
#define ti_lib_ssi_busy(...) SSIBusy(__VA_ARGS__)
#define ti_lib_ssi_status(...) SSIStatus(__VA_ARGS__)
#define ti_lib_ssi_int_register(...) SSIIntRegister(__VA_ARGS__)
#define ti_lib_ssi_int_unregister(...) SSIIntUnregister(__VA_ARGS__)
#define ti_lib_ssi_int_enable(...) SSIIntEnable(__VA_ARGS__)
#define ti_lib_ssi_int_disable(...) SSIIntDisable(__VA_ARGS__)
#define ti_lib_ssi_int_clear(...) SSIIntClear(__VA_ARGS__)
#define ti_lib_ssi_int_status(...) SSIIntStatus(__VA_ARGS__)
#define ti_lib_ssi_dma_enable(...) SSIDMAEnable(__VA_ARGS__)
#define ti_lib_ssi_dma_disable(...) SSIDMADisable(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* systick.h */
#include "driverlib/systick.h"
#define ti_lib_systick_enable(...) SysTickEnable(__VA_ARGS__)
#define ti_lib_systick_disable(...) SysTickDisable(__VA_ARGS__)
#define ti_lib_systick_int_register(...) SysTickIntRegister(__VA_ARGS__)
#define ti_lib_systick_int_unregister(...) SysTickIntUnregister(__VA_ARGS__)
#define ti_lib_systick_int_enable(...) SysTickIntEnable(__VA_ARGS__)
#define ti_lib_systick_int_disable(...) SysTickIntDisable(__VA_ARGS__)
#define ti_lib_systick_period_set(...) SysTickPeriodSet(__VA_ARGS__)
#define ti_lib_systick_period_get(...) SysTickPeriodGet(__VA_ARGS__)
#define ti_lib_systick_value_get(...) SysTickValueGet(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* timer.h */
#include "driverlib/timer.h"
#define ti_lib_timer_enable(...) TimerEnable(__VA_ARGS__)
#define ti_lib_timer_disable(...) TimerDisable(__VA_ARGS__)
#define ti_lib_timer_configure(...) TimerConfigure(__VA_ARGS__)
#define ti_lib_timer_level_control(...) TimerLevelControl(__VA_ARGS__)
#define ti_lib_timer_trigger_control(...) TimerTriggerControl(__VA_ARGS__)
#define ti_lib_timer_event_control(...) TimerEventControl(__VA_ARGS__)
#define ti_lib_timer_stall_control(...) TimerStallControl(__VA_ARGS__)
#define ti_lib_timer_wait_on_trigger_control(...) TimerWaitOnTriggerControl(__VA_ARGS__)
#define ti_lib_timer_rtc_enable(...) TimerRtcEnable(__VA_ARGS__)
#define ti_lib_timer_rtc_disable(...) TimerRtcDisable(__VA_ARGS__)
#define ti_lib_timer_prescale_set(...) TimerPrescaleSet(__VA_ARGS__)
#define ti_lib_timer_prescale_get(...) TimerPrescaleGet(__VA_ARGS__)
#define ti_lib_timer_prescale_match_set(...) TimerPrescaleMatchSet(__VA_ARGS__)
#define ti_lib_timer_prescale_match_get(...) TimerPrescaleMatchGet(__VA_ARGS__)
#define ti_lib_timer_load_set(...) TimerLoadSet(__VA_ARGS__)
#define ti_lib_timer_load_get(...) TimerLoadGet(__VA_ARGS__)
#define ti_lib_timer_value_get(...) TimerValueGet(__VA_ARGS__)
#define ti_lib_timer_match_set(...) TimerMatchSet(__VA_ARGS__)
#define ti_lib_timer_match_get(...) TimerMatchGet(__VA_ARGS__)
#define ti_lib_timer_int_register(...) TimerIntRegister(__VA_ARGS__)
#define ti_lib_timer_int_unregister(...) TimerIntUnregister(__VA_ARGS__)
#define ti_lib_timer_int_enable(...) TimerIntEnable(__VA_ARGS__)
#define ti_lib_timer_int_disable(...) TimerIntDisable(__VA_ARGS__)
#define ti_lib_timer_int_status(...) TimerIntStatus(__VA_ARGS__)
#define ti_lib_timer_int_clear(...) TimerIntClear(__VA_ARGS__)
#define ti_lib_timer_synchronize(...) TimerSynchronize(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* uart.h */
#include "driverlib/uart.h"
#define ti_lib_uart_parity_mode_set(...) UARTParityModeSet(__VA_ARGS__)
#define ti_lib_uart_parity_mode_get(...) UARTParityModeGet(__VA_ARGS__)
#define ti_lib_uart_fifo_level_set(...) UARTFIFOLevelSet(__VA_ARGS__)
#define ti_lib_uart_fifo_level_get(...) UARTFIFOLevelGet(__VA_ARGS__)
#define ti_lib_uart_config_set_exp_clk(...) UARTConfigSetExpClk(__VA_ARGS__)
#define ti_lib_uart_config_get_exp_clk(...) UARTConfigGetExpClk(__VA_ARGS__)
#define ti_lib_uart_enable(...) UARTEnable(__VA_ARGS__)
#define ti_lib_uart_disable(...) UARTDisable(__VA_ARGS__)
#define ti_lib_uart_fifo_enable(...) UARTFIFOEnable(__VA_ARGS__)
#define ti_lib_uart_fifo_disable(...) UARTFIFODisable(__VA_ARGS__)
#define ti_lib_uart_chars_avail(...) UARTCharsAvail(__VA_ARGS__)
#define ti_lib_uart_space_avail(...) UARTSpaceAvail(__VA_ARGS__)
#define ti_lib_uart_char_get_non_blocking(...) UARTCharGetNonBlocking(__VA_ARGS__)
#define ti_lib_uart_char_get(...) UARTCharGet(__VA_ARGS__)
#define ti_lib_uart_char_put_non_blocking(...) UARTCharPutNonBlocking(__VA_ARGS__)
#define ti_lib_uart_char_put(...) UARTCharPut(__VA_ARGS__)
#define ti_lib_uart_break_ctl(...) UARTBreakCtl(__VA_ARGS__)
#define ti_lib_uart_busy(...) UARTBusy(__VA_ARGS__)
#define ti_lib_uart_int_register(...) UARTIntRegister(__VA_ARGS__)
#define ti_lib_uart_int_unregister(...) UARTIntUnregister(__VA_ARGS__)
#define ti_lib_uart_int_enable(...) UARTIntEnable(__VA_ARGS__)
#define ti_lib_uart_int_disable(...) UARTIntDisable(__VA_ARGS__)
#define ti_lib_uart_int_status(...) UARTIntStatus(__VA_ARGS__)
#define ti_lib_uart_int_clear(...) UARTIntClear(__VA_ARGS__)
#define ti_lib_uart_dma_enable(...) UARTDMAEnable(__VA_ARGS__)
#define ti_lib_uart_dma_disable(...) UARTDMADisable(__VA_ARGS__)
#define ti_lib_uart_rx_error_get(...) UARTRxErrorGet(__VA_ARGS__)
#define ti_lib_uart_rx_error_clear(...) UARTRxErrorClear(__VA_ARGS__)
#define ti_lib_uart_tx_int_mode_set(...) UARTTxIntModeSet(__VA_ARGS__)
#define ti_lib_uart_tx_int_mode_get(...) UARTTxIntModeGet(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* vims.h */
#include "driverlib/vims.h"
#define ti_lib_vims_configure(...) VIMSConfigure(__VA_ARGS__)
#define ti_lib_vims_mode_set(...) VIMSModeSet(__VA_ARGS__)
#define ti_lib_vims_mode_get(...) VIMSModeGet(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
/* watchdog.h */
#include "driverlib/watchdog.h"
#define ti_lib_wathdog_running(...) WatchdogRunning(__VA_ARGS__)
#define ti_lib_wathdog_enable(...) WatchdogEnable(__VA_ARGS__)
#define ti_lib_wathdog_reset_enable(...) WatchdogResetEnable(__VA_ARGS__)
#define ti_lib_wathdog_reset_disable(...) WatchdogResetDisable(__VA_ARGS__)
#define ti_lib_wathdog_lock(...) WatchdogLock(__VA_ARGS__)
#define ti_lib_wathdog_unlock(...) WatchdogUnlock(__VA_ARGS__)
#define ti_lib_wathdog_lock_state(...) WatchdogLockState(__VA_ARGS__)
#define ti_lib_wathdog_reload_set(...) WatchdogReloadSet(__VA_ARGS__)
#define ti_lib_wathdog_reload_get(...) WatchdogReloadGet(__VA_ARGS__)
#define ti_lib_wathdog_value_get(...) WatchdogValueGet(__VA_ARGS__)
#define ti_lib_wathdog_int_register(...) WatchdogIntRegister(__VA_ARGS__)
#define ti_lib_wathdog_int_unregister(...) WatchdogIntUnregister(__VA_ARGS__)
#define ti_lib_wathdog_int_enable(...) WatchdogIntEnable(__VA_ARGS__)
#define ti_lib_wathdog_int_status(...) WatchdogIntStatus(__VA_ARGS__)
#define ti_lib_wathdog_int_clear(...) WatchdogIntClear(__VA_ARGS__)
#define ti_lib_wathdog_int_type_set(...) WatchdogIntTypeSet(__VA_ARGS__)
#define ti_lib_wathdog_stall_enable(...) WatchdogStallEnable(__VA_ARGS__)
#define ti_lib_wathdog_stall_disable(...) WatchdogStallDisable(__VA_ARGS__)
/*---------------------------------------------------------------------------*/
#endif /* TI_LIB_H_ */
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
*/