New Platform: TI CC2538 Development Kit

This commit adds cpu, platform and example files,
providing support for running Contiki on TI's cc2538 DK
This commit is contained in:
George Oikonomou 2013-01-12 22:44:42 +00:00
parent d5d8de7372
commit 40f49948e6
74 changed files with 13125 additions and 0 deletions

View File

@ -0,0 +1,86 @@
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
NM = arm-none-eabi-nm
LDSCRIPT = $(OBJECTDIR)/cc2538.ld
CFLAGS += -O2 -mcpu=cortex-m3 -mthumb -mlittle-endian
CFLAGS += -fshort-enums -fomit-frame-pointer -fno-strict-aliasing
CFLAGS += -Wall
LDFLAGS += -mcpu=cortex-m3 -mthumb -nostartfiles
LDFLAGS += -T $(LDSCRIPT)
LDFLAGS += -Wl,-Map=$(@:.elf=-$(TARGET).map),--cref,--no-warn-mismatch
OBJCOPY_FLAGS += -O binary --gap-fill 0xff
### Are we building with code size optimisations?
ifeq ($(SMALL),1)
CFLAGS += -ffunction-sections -fdata-sections
LDFLAGS += -Wl,--gc-sections
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
### CPU-dependent directories
CONTIKI_CPU_DIRS = . dev usb
### Use the existing debug I/O in cpu/arm/common
CONTIKI_CPU_DIRS += ../arm/common/dbg-io
### Use usb core from cpu/cc253x/usb/common
CONTIKI_CPU_DIRS += ../cc253x/usb/common ../cc253x/usb/common/cdc-acm
### CPU-dependent source files
CONTIKI_CPU_SOURCEFILES += clock.c rtimer-arch.c uart.c watchdog.c
CONTIKI_CPU_SOURCEFILES += nvic.c cpu.c sys-ctrl.c gpio.c ioc.c
CONTIKI_CPU_SOURCEFILES += cc2538-rf.c udma.c lpm.c
CONTIKI_CPU_SOURCEFILES += dbg.c ieee-addr.c
CONTIKI_CPU_SOURCEFILES += slip-arch.c slip.c
DEBUG_IO_SOURCEFILES += dbg-printf.c dbg-snprintf.c dbg-sprintf.c strformat.c
USB_CORE_SOURCEFILES += usb-core.c cdc-acm.c
USB_ARCH_SOURCEFILES += usb-arch.c usb-serial.c cdc-acm-descriptors.c
CONTIKI_SOURCEFILES += $(CONTIKI_CPU_SOURCEFILES) $(DEBUG_IO_SOURCEFILES)
CONTIKI_SOURCEFILES += $(USB_CORE_SOURCEFILES) $(USB_ARCH_SOURCEFILES)
### Don't treat the .elf as intermediate
.PRECIOUS: %.elf %.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
$(CC) $(CFLAGS) -c $< -o $@
### Compilation rules
CUSTOM_RULE_LINK=1
%.elf: $(TARGET_STARTFILES) %.co $(PROJECT_OBJECTFILES) $(PROJECT_LIBRARIES) contiki-$(TARGET).a $(LDSCRIPT)
$(LD) $(LDFLAGS) ${filter-out $(LDSCRIPT) %.a,$^} ${filter %.a,$^} -o $@
%.bin: %.elf
$(OBJCOPY) $(OBJCOPY_FLAGS) $< $@
### We don't really need the .bin for the .$(TARGET) but let's make sure it
### gets built
%.$(TARGET): %.elf %.bin
cp $< $@
### This rule is used to generate the correct linker script
LDGENFLAGS += $(addprefix -D,$(subst $(COMMA), ,$(DEFINES)))
LDGENFLAGS += $(addprefix -I,$(SOURCEDIRS))
LDGENFLAGS += -imacros "contiki-conf.h"
LDGENFLAGS += -P -E
$(LDSCRIPT): $(CONTIKI_CPU)/cc2538.lds FORCE
$(CPP) $(LDGENFLAGS) $< -o $@

87
cpu/cc2538/cc2538.lds Normal file
View File

@ -0,0 +1,87 @@
/*
* Copyright (c) 2013, 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.
*/
/*
* cc2538 linker configuration file. This is not the actual file used at link
* stage. Rather, it is used as input for the auto-generation of the actual
* ld script, which is called cc2538.ld and will be in the project directory
*/
#if (LPM_CONF_MAX_PM==2) && (LPM_CONF_ENABLE != 0)
#define SRAM_START 0x20004000
#define SRAM_LEN 0x00004000
#else
#define SRAM_START 0x20000000
#define SRAM_LEN 0x00008000
#endif
MEMORY
{
FLASH (rx) : ORIGIN = 0x200000, LENGTH = 0x0007FFD4
FLASH_CCA (RX) : ORIGIN = 0x0027FFD4, LENGTH = 12
SRAM (RWX) : ORIGIN = SRAM_START, LENGTH = SRAM_LEN
}
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
.flashcca :
{
KEEP(*(.flashcca))
} > FLASH_CCA
}

227
cpu/cc2538/clock.c Normal file
View File

@ -0,0 +1,227 @@
/*
* 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 cc2538
* @{
*
* \defgroup cc2538-clock cc2538 Clock
*
* Implementation of the clock module for the cc2538
*
* To implement the clock functionality, we use the SysTick peripheral on the
* cortex-M3. We run the system clock at 16 MHz and we set the SysTick to give
* us 128 interrupts / sec
* @{
*
* \file
* Clock driver implementation for the TI cc2538
*/
#include "contiki.h"
#include "systick.h"
#include "reg.h"
#include "cpu.h"
#include "dev/gptimer.h"
#include "dev/sys-ctrl.h"
#include "sys/energest.h"
#include <stdint.h>
/*---------------------------------------------------------------------------*/
#define RELOAD_VALUE (125000 - 1) /** Fire 128 times / sec */
static volatile clock_time_t count;
static volatile unsigned long secs = 0;
static volatile uint8_t second_countdown = CLOCK_SECOND;
/*---------------------------------------------------------------------------*/
/**
* \brief Arch-specific implementation of clock_init for the cc2538
*
* We initialise the SysTick to fire 128 interrupts per second, giving us a
* value of 128 for CLOCK_SECOND
*
* We also initialise GPT0:Timer A, which is used by clock_delay_usec().
* We use 16-bit range (individual), count-down, one-shot, no interrupts.
* The system clock is at 16MHz giving us 62.5 nano sec ticks for Timer A.
* Prescaled by 16 gives us a very convenient 1 tick per usec
*/
void
clock_init(void)
{
count = 0;
REG(SYSTICK_STRELOAD) = RELOAD_VALUE;
/* System clock source, Enable */
REG(SYSTICK_STCTRL) |= SYSTICK_STCTRL_CLK_SRC | SYSTICK_STCTRL_ENABLE;
/* Enable the SysTick Interrupt */
REG(SYSTICK_STCTRL) |= SYSTICK_STCTRL_INTEN;
/*
* Remove the clock gate to enable GPT0 and then initialise it
* We only use GPT0 for clock_delay_usec. We initialise it here so we can
* have it ready when it's needed
*/
REG(SYS_CTRL_RCGCGPT) |= SYS_CTRL_RCGCGPT_GPT0;
/* Make sure GPT0 is off */
REG(GPT_0_BASE | GPTIMER_CTL) = 0;
/* 16-bit */
REG(GPT_0_BASE | GPTIMER_CFG) = 0x04;
/* One-Shot, Count Down, No Interrupts */
REG(GPT_0_BASE | GPTIMER_TAMR) = GPTIMER_TAMR_TAMR_ONE_SHOT;
/* Prescale by 16 (thus, value 15 in TAPR) */
REG(GPT_0_BASE | GPTIMER_TAPR) = 0x0F;
}
/*---------------------------------------------------------------------------*/
CCIF clock_time_t
clock_time(void)
{
return count;
}
/*---------------------------------------------------------------------------*/
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);
}
/*---------------------------------------------------------------------------*/
/**
* \brief Arch-specific implementation of clock_delay_usec for the cc2538
* \param len Delay \e len uSecs
*
* See clock_init() for GPT0 Timer A's configuration
*/
void
clock_delay_usec(uint16_t len)
{
REG(GPT_0_BASE | GPTIMER_TAILR) = len;
REG(GPT_0_BASE | GPTIMER_CTL) |= GPTIMER_CTL_TAEN;
/* One-Shot mode: TAEN will be cleared when the timer reaches 0 */
while(REG(GPT_0_BASE | GPTIMER_CTL) & GPTIMER_CTL_TAEN);
}
/*---------------------------------------------------------------------------*/
/**
* \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);
}
/*---------------------------------------------------------------------------*/
/**
* \brief Adjust the clock by moving it forward by a number of ticks
* \param ticks The number of ticks
*
* This function is useful when coming out of PM1/2, during which the system
* clock is stopped. We adjust the clock by moving it forward by a number of
* ticks equal to the deep sleep duration. We update the seconds counter if
* we have to and we also do some housekeeping so that the next second will
* increment when it is meant to.
*
* \note This function is only meant to be used by lpm_exit(). Applications
* should really avoid calling this
*/
void
clock_adjust(clock_time_t ticks)
{
/* Halt the SysTick while adjusting */
REG(SYSTICK_STCTRL) &= ~SYSTICK_STCTRL_ENABLE;
/* Moving forward by more than a second? */
secs += ticks >> 7;
/* Increment tick count */
count += ticks;
/*
* Update internal second countdown so that next second change will actually
* happen when it's meant to happen.
*/
second_countdown -= ticks;
if(second_countdown == 0 || second_countdown > 128) {
secs++;
second_countdown -= 128;
}
/* Re-Start the SysTick */
REG(SYSTICK_STCTRL) |= SYSTICK_STCTRL_ENABLE;
}
/*---------------------------------------------------------------------------*/
/**
* \brief The clock Interrupt Service Routine. It polls the etimer process
* if an etimer has expired. It also updates the software clock tick and
* seconds counter since reset.
*/
void
clock_isr(void)
{
ENERGEST_ON(ENERGEST_TYPE_IRQ);
count++;
if(etimer_pending()) {
etimer_request_poll();
}
if(--second_countdown == 0) {
secs++;
second_countdown = CLOCK_SECOND;
}
ENERGEST_OFF(ENERGEST_TYPE_IRQ);
}
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
*/

72
cpu/cc2538/cpu.c Normal file
View File

@ -0,0 +1,72 @@
/*
* 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 cc2538-cpu
* @{
*
* \file
* Implementations of interrupt control on the cc2538 Cortex-M3 micro
*/
/*---------------------------------------------------------------------------*/
unsigned long __attribute__((naked))
cpu_cpsie(void)
{
unsigned long ret;
/* Read PRIMASK and enable interrupts */
__asm(" mrs r0, PRIMASK\n"
" cpsie i\n"
" bx lr\n"
: "=r" (ret));
/* The inline asm returns, we never reach here.
* We add a return statement to keep the compiler happy */
return ret;
}
/*---------------------------------------------------------------------------*/
unsigned long __attribute__((naked))
cpu_cpsid(void)
{
unsigned long ret;
/* Read PRIMASK and disable interrupts */
__asm(" mrs r0, PRIMASK\n"
" cpsid i\n"
" bx lr\n"
: "=r" (ret));
/* The inline asm returns, we never reach here.
* We add a return statement to keep the compiler happy */
return ret;
}
/*---------------------------------------------------------------------------*/
/** @} */

65
cpu/cc2538/cpu.h Normal file
View File

@ -0,0 +1,65 @@
/*
* 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 cc2538
* @{
*
* \defgroup cc2538-cpu cc2538 CPU
*
* cc2538 CPU-specific functions for the cc2538 core
* @{
*
* \file
* Header file with prototypes for interrupt control on the cc2538
* Cortex-M3 micro
*
*/
#ifndef CPU_H_
#define CPU_H_
/** \brief Disables all CPU interrupts */
unsigned long cpu_cpsid(void);
/** \brief Enables all CPU interrupts */
unsigned long cpu_cpsie(void);
/** \brief Enables all CPU interrupts */
#define INTERRUPTS_ENABLE() cpu_cpsie()
/** \brief Disables all CPU interrupts. */
#define INTERRUPTS_DISABLE() cpu_cpsid()
#endif /* CPU_H_ */
/**
* @}
* @}
*/

117
cpu/cc2538/dbg.c Normal file
View File

@ -0,0 +1,117 @@
/*
* 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 cc2538-char-io
* @{ */
/**
* \file
* Implementation of arch-specific functions required by the dbg_io API in
* cpu/arm/common/dbg-io
*/
#include "contiki.h"
#include "dbg.h"
#include "dev/uart.h"
#include "usb/usb-serial.h"
#include <stdio.h>
/*---------------------------------------------------------------------------*/
#ifndef DBG_CONF_USB
#define DBG_CONF_USB 0
#endif
#if DBG_CONF_USB
#define write_byte(b) usb_serial_writeb(b)
#define flush() usb_serial_flush()
#else
#define write_byte(b) uart_write_byte(b)
#define flush()
#endif
/*---------------------------------------------------------------------------*/
#undef putchar
#undef puts
#define SLIP_END 0300
/*---------------------------------------------------------------------------*/
int
putchar(int c)
{
#if DBG_CONF_SLIP_MUX
static char debug_frame = 0;
if(!debug_frame) {
write_byte(SLIP_END);
write_byte('\r');
debug_frame = 1;
}
#endif
write_byte(c);
if(c == '\n') {
#if DBG_CONF_SLIP_MUX
write_byte(SLIP_END);
debug_frame = 0;
#endif
dbg_flush();
}
return c;
}
/*---------------------------------------------------------------------------*/
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;
}
/*---------------------------------------------------------------------------*/
int
puts(const char *s)
{
unsigned int i = 0;
while(s && *s != 0) {
putchar(*s++);
i++;
}
putchar('\n');
return i;
}
/*---------------------------------------------------------------------------*/
/** @} */

91
cpu/cc2538/dbg.h Normal file
View File

@ -0,0 +1,91 @@
/*
* 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 cc2538
* @{
*
* \defgroup cc2538-char-io cc2538 Character I/O
*
* cc2538 CPU-specific functions for debugging and SLIP I/O
*
* On the cc2538, character I/O can be directed over USB or UART. This is
* controlled by a series of configuration directives:
* - SLIP_ARCH_CONF_USB: Controls the operation of slip-arch.
* - CC2538_RF_CONF_SNIFFER_USB: Controls the output of the RF driver when
* operating as a sniffer
* - DBG_CONF_USB: Controls all debugging output
*
* Defaults for those defines are set in contiki-conf.h
* @{
*
* \file
* Header file for the cc2538 Debug I/O module
*/
#ifndef DBG_H_
#define DBG_H_
#include "contiki-conf.h"
#include "usb/usb-serial.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);
/**
* \brief Flushes character output
*
* When debugging is sent over USB, this functions causes the USB
* driver to immediately TX the content of output buffers. When
* debugging is over UART, this function does nothing.
*
* There is nothing stopping you from using this macro in your code but
* normally, you won't have to.
*/
#if DBG_CONF_USB
#define dbg_flush() usb_serial_flush()
#else
#define dbg_flush()
#endif
#endif /* DBG_H_ */
/**
* @}
* @}
*/

47
cpu/cc2538/debug-uart.h Normal file
View File

@ -0,0 +1,47 @@
/*
* 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 cc2538-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_ */
/** @} */

60
cpu/cc2538/dev/ana-regs.h Normal file
View File

@ -0,0 +1,60 @@
/*
* 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 cc2538-rfcore
* @{
*
* \file
* Header with declarations of ANA_REGS module registers.
*/
#ifndef ANA_REGS_H
#define ANA_REGS_H
/*---------------------------------------------------------------------------*/
/**
* \name ANA_REGS register offsets
* @{
*/
#define ANA_REGS_IVCTRL 0x00000004
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name ANA_REGS_IVCTRL register bit masks
* @{
*/
#define ANA_REGS_IVCTRL_DAC_CURR_CTRL 0x00000030 /**< Controls bias current to DAC */
#define ANA_REGS_IVCTRL_LODIV_BIAS_CTRL 0x00000008 /**< Controls bias current to LODIV */
#define ANA_REGS_IVCTRL_TXMIX_DC_CTRL 0x00000004 /**< Controls DC bias in TXMIX */
#define ANA_REGS_IVCTRL_PA_BIAS_CTRL 0x00000003 /**< Controls bias current to PA */
/** @} */
#endif /* ANA_REGS_H */
/** @} */

724
cpu/cc2538/dev/cc2538-rf.c Normal file
View File

@ -0,0 +1,724 @@
/*
* 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 cc2538-rf
* @{
*
* \file
* Implementation of the cc2538 RF driver
*/
#include "contiki.h"
#include "dev/radio.h"
#include "sys/clock.h"
#include "sys/rtimer.h"
#include "net/packetbuf.h"
#include "net/rime/rimestats.h"
#include "net/rime/rimeaddr.h"
#include "net/netstack.h"
#include "sys/energest.h"
#include "dev/cc2538-rf.h"
#include "dev/rfcore.h"
#include "dev/sys-ctrl.h"
#include "dev/udma.h"
#include "reg.h"
#include <string.h>
/*---------------------------------------------------------------------------*/
#define CHECKSUM_LEN 2
/* uDMA channel control persistent flags */
#define UDMA_TX_FLAGS (UDMA_CHCTL_ARBSIZE_128 | UDMA_CHCTL_XFERMODE_AUTO \
| UDMA_CHCTL_SRCSIZE_8 | UDMA_CHCTL_DSTSIZE_8 \
| UDMA_CHCTL_SRCINC_8 | UDMA_CHCTL_DSTINC_NONE)
#define UDMA_RX_FLAGS (UDMA_CHCTL_ARBSIZE_128 | UDMA_CHCTL_XFERMODE_AUTO \
| UDMA_CHCTL_SRCSIZE_8 | UDMA_CHCTL_DSTSIZE_8 \
| UDMA_CHCTL_SRCINC_NONE | UDMA_CHCTL_DSTINC_8)
/*
* uDMA transfer threshold. DMA will only be used to read an incoming frame
* if its size is above this threshold
*/
#define UDMA_RX_SIZE_THRESHOLD 3
/*---------------------------------------------------------------------------*/
#include <stdio.h>
#define DEBUG 0
#if DEBUG
#define PRINTF(...) printf(__VA_ARGS__)
#else
#define PRINTF(...)
#endif
/*---------------------------------------------------------------------------*/
/* Local RF Flags */
#define RX_ACTIVE 0x80
#define RF_MUST_RESET 0x40
#define WAS_OFF 0x10
#define RF_ON 0x01
/* Bit Masks for the last byte in the RX FIFO */
#define CRC_BIT_MASK 0x80
#define LQI_BIT_MASK 0x7F
/* RSSI Offset */
#define RSSI_OFFSET 73
/* 192 usec off -> on interval (RX Callib -> SFD Wait). We wait a bit more */
#define ONOFF_TIME RTIMER_ARCH_SECOND / 3125
/*---------------------------------------------------------------------------*/
/* Sniffer configuration */
#ifndef CC2538_RF_CONF_SNIFFER_USB
#define CC2538_RF_CONF_SNIFFER_USB 0
#endif
#if CC2538_RF_CONF_SNIFFER
static const uint8_t magic[] = { 0x53, 0x6E, 0x69, 0x66 }; /** Snif */
#if CC2538_RF_CONF_SNIFFER_USB
#include "usb/usb-serial.h"
#define write_byte(b) usb_serial_writeb(b)
#define flush() usb_serial_flush()
#else
#include "dev/uart.h"
#define write_byte(b) uart_write_byte(b)
#define flush()
#endif
#else /* CC2538_RF_CONF_SNIFFER */
#define write_byte(b)
#define flush()
#endif /* CC2538_RF_CONF_SNIFFER */
/*---------------------------------------------------------------------------*/
#ifdef CC2538_RF_CONF_AUTOACK
#define CC2538_RF_AUTOACK CC2538_RF_CONF_AUTOACK
#else
#define CC2538_RF_AUTOACK 1
#endif
/*---------------------------------------------------------------------------*/
static uint8_t rf_flags;
static int on(void);
static int off(void);
/*---------------------------------------------------------------------------*/
PROCESS(cc2538_rf_process, "cc2538 RF driver");
/*---------------------------------------------------------------------------*/
uint8_t
cc2538_rf_channel_get()
{
uint8_t chan = REG(RFCORE_XREG_FREQCTRL) & RFCORE_XREG_FREQCTRL_FREQ;
return ((chan - CC2538_RF_CHANNEL_MIN) / CC2538_RF_CHANNEL_SPACING
+ CC2538_RF_CHANNEL_MIN);
}
/*---------------------------------------------------------------------------*/
int8_t
cc2538_rf_channel_set(uint8_t channel)
{
PRINTF("RF: Set Channel\n");
if((channel < CC2538_RF_CHANNEL_MIN) || (channel > CC2538_RF_CHANNEL_MAX)) {
return -1;
}
/* Changes to FREQCTRL take effect after the next recalibration */
off();
REG(RFCORE_XREG_FREQCTRL) = (CC2538_RF_CHANNEL_MIN
+ (channel - CC2538_RF_CHANNEL_MIN) * CC2538_RF_CHANNEL_SPACING);
on();
return (int8_t) channel;
}
/*---------------------------------------------------------------------------*/
uint8_t
cc2538_rf_power_set(uint8_t new_power)
{
PRINTF("RF: Set Power\n");
REG(RFCORE_XREG_TXPOWER) = new_power;
return (REG(RFCORE_XREG_TXPOWER) & 0xFF);
}
/*---------------------------------------------------------------------------*/
/* ToDo: Check once we have info on the... infopage */
void
cc2538_rf_set_addr(uint16_t pan)
{
#if RIMEADDR_SIZE==8
/* EXT_ADDR[7:0] is ignored when using short addresses */
int i;
for(i = (RIMEADDR_SIZE - 1); i >= 0; --i) {
((uint32_t *)RFCORE_FFSM_EXT_ADDR0)[i] =
rimeaddr_node_addr.u8[RIMEADDR_SIZE - 1 - i];
}
#endif
REG(RFCORE_FFSM_PAN_ID0) = pan & 0xFF;
REG(RFCORE_FFSM_PAN_ID1) = pan >> 8;
REG(RFCORE_FFSM_SHORT_ADDR0) = rimeaddr_node_addr.u8[RIMEADDR_SIZE - 1];
REG(RFCORE_FFSM_SHORT_ADDR1) = rimeaddr_node_addr.u8[RIMEADDR_SIZE - 2];
}
/*---------------------------------------------------------------------------*/
/* Netstack API radio driver functions */
/*---------------------------------------------------------------------------*/
static int
channel_clear(void)
{
int cca;
PRINTF("RF: CCA\n");
/* If we are off, turn on first */
if((REG(RFCORE_XREG_FSMSTAT0) & RFCORE_XREG_FSMSTAT0_FSM_FFCTRL_STATE) == 0) {
rf_flags |= WAS_OFF;
on();
}
/* Wait on RSSI_VALID */
while((REG(RFCORE_XREG_RSSISTAT) & RFCORE_XREG_RSSISTAT_RSSI_VALID) == 0);
if(REG(RFCORE_XREG_FSMSTAT1) & RFCORE_XREG_FSMSTAT1_CCA) {
cca = CC2538_RF_CCA_CLEAR;
} else {
cca = CC2538_RF_CCA_BUSY;
}
/* If we were off, turn back off */
if((rf_flags & WAS_OFF) == WAS_OFF) {
rf_flags &= ~WAS_OFF;
off();
}
return cca;
}
/*---------------------------------------------------------------------------*/
static int
on(void)
{
PRINTF("RF: On\n");
if(!(rf_flags & RX_ACTIVE)) {
CC2538_RF_CSP_ISFLUSHRX();
CC2538_RF_CSP_ISRXON();
rf_flags |= RX_ACTIVE;
}
ENERGEST_ON(ENERGEST_TYPE_LISTEN);
return 1;
}
/*---------------------------------------------------------------------------*/
static int
off(void)
{
PRINTF("RF: Off\n");
/* Wait for ongoing TX to complete (e.g. this could be an outgoing ACK) */
while(REG(RFCORE_XREG_FSMSTAT1) & RFCORE_XREG_FSMSTAT1_TX_ACTIVE);
CC2538_RF_CSP_ISFLUSHRX();
/* Don't turn off if we are off as this will trigger a Strobe Error */
if(REG(RFCORE_XREG_RXENABLE) != 0) {
CC2538_RF_CSP_ISRFOFF();
}
rf_flags &= ~RX_ACTIVE;
ENERGEST_OFF(ENERGEST_TYPE_LISTEN);
return 1;
}
/*---------------------------------------------------------------------------*/
static int
init(void)
{
PRINTF("RF: Init\n");
if(rf_flags & RF_ON) {
return 0;
}
/* Enable clock for the RF Core while Running, in Sleep and Deep Sleep */
REG(SYS_CTRL_RCGCRFC) = 1;
REG(SYS_CTRL_SCGCRFC) = 1;
REG(SYS_CTRL_DCGCRFC) = 1;
REG(RFCORE_XREG_CCACTRL0) = CC2538_RF_CCA_THRES_USER_GUIDE;
/*
* Changes from default values
* See User Guide, section "Register Settings Update"
*/
REG(RFCORE_XREG_TXFILTCFG) = 0x09; /** TX anti-aliasing filter bandwidth */
REG(RFCORE_XREG_AGCCTRL1) = 0x15; /** AGC target value */
REG(ANA_REGS_IVCTRL) = 0x0B; /** Bias currents */
/*
* Defaults:
* Auto CRC; Append RSSI, CRC-OK and Corr. Val.; CRC calculation;
* RX and TX modes with FIFOs
*/
REG(RFCORE_XREG_FRMCTRL0) = RFCORE_XREG_FRMCTRL0_AUTOCRC;
#if CC2538_RF_AUTOACK
REG(RFCORE_XREG_FRMCTRL0) |= RFCORE_XREG_FRMCTRL0_AUTOACK;
#endif
/* If we are a sniffer, turn off frame filtering */
#if CC2538_RF_CONF_SNIFFER
REG(RFCORE_XREG_FRMFILT0) &= ~RFCORE_XREG_FRMFILT0_FRAME_FILTER_EN;
#endif
/* Disable source address matching and autopend */
REG(RFCORE_XREG_SRCMATCH) = 0;
/* MAX FIFOP threshold */
REG(RFCORE_XREG_FIFOPCTRL) = CC2538_RF_MAX_PACKET_LEN;
cc2538_rf_power_set(CC2538_RF_TX_POWER);
cc2538_rf_channel_set(CC2538_RF_CHANNEL);
/* Acknowledge RF interrupts, FIFOP only */
REG(RFCORE_XREG_RFIRQM0) |= RFCORE_XREG_RFIRQM0_FIFOP;
nvic_interrupt_enable(NVIC_INT_RF_RXTX);
/* Acknowledge all RF Error interrupts */
REG(RFCORE_XREG_RFERRM) = RFCORE_XREG_RFERRM_RFERRM;
nvic_interrupt_enable(NVIC_INT_RF_ERR);
if(CC2538_RF_CONF_TX_USE_DMA) {
/* Disable peripheral triggers for the channel */
udma_channel_mask_set(CC2538_RF_CONF_TX_DMA_CHAN);
/*
* Set the channel's DST. SRC can not be set yet since it will change for
* each transfer
*/
udma_set_channel_dst(CC2538_RF_CONF_TX_DMA_CHAN, RFCORE_SFR_RFDATA);
}
if(CC2538_RF_CONF_RX_USE_DMA) {
/* Disable peripheral triggers for the channel */
udma_channel_mask_set(CC2538_RF_CONF_RX_DMA_CHAN);
/*
* Set the channel's SRC. DST can not be set yet since it will change for
* each transfer
*/
udma_set_channel_src(CC2538_RF_CONF_RX_DMA_CHAN, RFCORE_SFR_RFDATA);
}
process_start(&cc2538_rf_process, NULL);
rf_flags |= RF_ON;
ENERGEST_ON(ENERGEST_TYPE_LISTEN);
return 1;
}
/*---------------------------------------------------------------------------*/
static int
prepare(const void *payload, unsigned short payload_len)
{
uint8_t i;
PRINTF("RF: Prepare 0x%02x bytes\n", payload_len + CHECKSUM_LEN);
/*
* When we transmit in very quick bursts, make sure previous transmission
* is not still in progress before re-writing to the TX FIFO
*/
while(REG(RFCORE_XREG_FSMSTAT1) & RFCORE_XREG_FSMSTAT1_TX_ACTIVE);
if((rf_flags & RX_ACTIVE) == 0) {
on();
}
CC2538_RF_CSP_ISFLUSHTX();
PRINTF("RF: data = ");
/* Send the phy length byte first */
REG(RFCORE_SFR_RFDATA) = payload_len + CHECKSUM_LEN;
if(CC2538_RF_CONF_TX_USE_DMA) {
PRINTF("<uDMA payload>");
/* Set the transfer source's end address */
udma_set_channel_src(CC2538_RF_CONF_TX_DMA_CHAN,
(uint32_t)(payload) + payload_len - 1);
/* Configure the control word */
udma_set_channel_control_word(CC2538_RF_CONF_TX_DMA_CHAN,
UDMA_TX_FLAGS | udma_xfer_size(payload_len));
/* Enabled the RF TX uDMA channel */
udma_channel_enable(CC2538_RF_CONF_TX_DMA_CHAN);
/* Trigger the uDMA transfer */
udma_channel_sw_request(CC2538_RF_CONF_TX_DMA_CHAN);
/*
* No need to wait for this to end. Even if transmit() gets called
* immediately, the uDMA controller will stream the frame to the TX FIFO
* faster than transmit() can empty it
*/
} else {
for(i = 0; i < payload_len; i++) {
REG(RFCORE_SFR_RFDATA) = ((unsigned char *)(payload))[i];
PRINTF("%02x", ((unsigned char *)(payload))[i]);
}
}
PRINTF("\n");
return 0;
}
/*---------------------------------------------------------------------------*/
static int
transmit(unsigned short transmit_len)
{
uint8_t counter;
int ret = RADIO_TX_ERR;
rtimer_clock_t t0;
PRINTF("RF: Transmit\n");
if(!(rf_flags & RX_ACTIVE)) {
t0 = RTIMER_NOW();
on();
rf_flags |= WAS_OFF;
while(RTIMER_CLOCK_LT(RTIMER_NOW(), t0 + ONOFF_TIME));
}
if(channel_clear() == CC2538_RF_CCA_BUSY) {
RIMESTATS_ADD(contentiondrop);
return RADIO_TX_COLLISION;
}
/*
* prepare() double checked that TX_ACTIVE is low. If SFD is high we are
* receiving. Abort transmission and bail out with RADIO_TX_COLLISION
*/
if(REG(RFCORE_XREG_FSMSTAT1) & RFCORE_XREG_FSMSTAT1_SFD) {
RIMESTATS_ADD(contentiondrop);
return RADIO_TX_COLLISION;
}
/* Start the transmission */
ENERGEST_OFF(ENERGEST_TYPE_LISTEN);
ENERGEST_ON(ENERGEST_TYPE_TRANSMIT);
CC2538_RF_CSP_ISTXON();
counter = 0;
while(!((REG(RFCORE_XREG_FSMSTAT1) & RFCORE_XREG_FSMSTAT1_TX_ACTIVE))
&& (counter++ < 3)) {
clock_delay_usec(6);
}
if(!(REG(RFCORE_XREG_FSMSTAT1) & RFCORE_XREG_FSMSTAT1_TX_ACTIVE)) {
PRINTF("RF: TX never active.\n");
CC2538_RF_CSP_ISFLUSHTX();
ret = RADIO_TX_ERR;
} else {
/* Wait for the transmission to finish */
while(REG(RFCORE_XREG_FSMSTAT1) & RFCORE_XREG_FSMSTAT1_TX_ACTIVE);
ret = RADIO_TX_OK;
}
ENERGEST_OFF(ENERGEST_TYPE_TRANSMIT);
ENERGEST_ON(ENERGEST_TYPE_LISTEN);
if(rf_flags & WAS_OFF) {
rf_flags &= ~WAS_OFF;
off();
}
RIMESTATS_ADD(lltx);
return ret;
}
/*---------------------------------------------------------------------------*/
static int
send(const void *payload, unsigned short payload_len)
{
prepare(payload, payload_len);
return transmit(payload_len);
}
/*---------------------------------------------------------------------------*/
static int
read(void *buf, unsigned short bufsize)
{
uint8_t i;
uint8_t len;
uint8_t crc_corr;
int8_t rssi;
PRINTF("RF: Read\n");
if((REG(RFCORE_XREG_FSMSTAT1) & RFCORE_XREG_FSMSTAT1_FIFOP) == 0) {
return 0;
}
/* Check the length */
len = REG(RFCORE_SFR_RFDATA);
/* Check for validity */
if(len > CC2538_RF_MAX_PACKET_LEN) {
/* Oops, we must be out of sync. */
PRINTF("RF: bad sync\n");
RIMESTATS_ADD(badsynch);
CC2538_RF_CSP_ISFLUSHRX();
return 0;
}
if(len <= CC2538_RF_MIN_PACKET_LEN) {
PRINTF("RF: too short\n");
RIMESTATS_ADD(tooshort);
CC2538_RF_CSP_ISFLUSHRX();
return 0;
}
if(len - CHECKSUM_LEN > bufsize) {
PRINTF("RF: too long\n");
RIMESTATS_ADD(toolong);
CC2538_RF_CSP_ISFLUSHRX();
return 0;
}
/* If we reach here, chances are the FIFO is holding a valid frame */
PRINTF("RF: read (0x%02x bytes) = ", len);
len -= CHECKSUM_LEN;
/* Don't bother with uDMA for short frames (e.g. ACKs) */
if(CC2538_RF_CONF_RX_USE_DMA && len > UDMA_RX_SIZE_THRESHOLD) {
PRINTF("<uDMA payload>");
/* Set the transfer destination's end address */
udma_set_channel_dst(CC2538_RF_CONF_RX_DMA_CHAN,
(uint32_t)(buf) + len - 1);
/* Configure the control word */
udma_set_channel_control_word(CC2538_RF_CONF_RX_DMA_CHAN,
UDMA_RX_FLAGS | udma_xfer_size(len));
/* Enabled the RF RX uDMA channel */
udma_channel_enable(CC2538_RF_CONF_RX_DMA_CHAN);
/* Trigger the uDMA transfer */
udma_channel_sw_request(CC2538_RF_CONF_RX_DMA_CHAN);
/* Wait for the transfer to complete. */
while(udma_channel_get_mode(CC2538_RF_CONF_RX_DMA_CHAN));
} else {
for(i = 0; i < len; ++i) {
((unsigned char *)(buf))[i] = REG(RFCORE_SFR_RFDATA);
PRINTF("%02x", ((unsigned char *)(buf))[i]);
}
}
/* Read the RSSI and CRC/Corr bytes */
rssi = ((int8_t)REG(RFCORE_SFR_RFDATA)) - RSSI_OFFSET;
crc_corr = REG(RFCORE_SFR_RFDATA);
PRINTF("%02x%02x\n", (uint8_t)rssi, crc_corr);
/* MS bit CRC OK/Not OK, 7 LS Bits, Correlation value */
if(crc_corr & CRC_BIT_MASK) {
packetbuf_set_attr(PACKETBUF_ATTR_RSSI, rssi);
packetbuf_set_attr(PACKETBUF_ATTR_LINK_QUALITY, crc_corr & LQI_BIT_MASK);
RIMESTATS_ADD(llrx);
} else {
RIMESTATS_ADD(badcrc);
PRINTF("RF: Bad CRC\n");
CC2538_RF_CSP_ISFLUSHRX();
return 0;
}
#if CC2538_RF_CONF_SNIFFER
write_byte(magic[0]);
write_byte(magic[1]);
write_byte(magic[2]);
write_byte(magic[3]);
write_byte(len + 2);
for(i = 0; i < len; ++i) {
write_byte(((unsigned char *)(buf))[i]);
}
write_byte(rssi);
write_byte(crc_corr);
flush();
#endif
/* If FIFOP==1 and FIFO==0 then we had a FIFO overflow at some point. */
if(REG(RFCORE_XREG_FSMSTAT1) & RFCORE_XREG_FSMSTAT1_FIFOP) {
if(REG(RFCORE_XREG_FSMSTAT1) & RFCORE_XREG_FSMSTAT1_FIFO) {
process_poll(&cc2538_rf_process);
} else {
CC2538_RF_CSP_ISFLUSHRX();
}
}
return (len);
}
/*---------------------------------------------------------------------------*/
static int
receiving_packet(void)
{
PRINTF("RF: Receiving\n");
/*
* SFD high while transmitting and receiving.
* TX_ACTIVE high only when transmitting
*
* FSMSTAT1 & (TX_ACTIVE | SFD) == SFD <=> receiving
*/
return ((REG(RFCORE_XREG_FSMSTAT1)
& (RFCORE_XREG_FSMSTAT1_TX_ACTIVE | RFCORE_XREG_FSMSTAT1_SFD))
== RFCORE_XREG_FSMSTAT1_SFD);
}
/*---------------------------------------------------------------------------*/
static int
pending_packet(void)
{
PRINTF("RF: Pending\n");
return (REG(RFCORE_XREG_FSMSTAT1) & RFCORE_XREG_FSMSTAT1_FIFOP);
}
/*---------------------------------------------------------------------------*/
const struct radio_driver cc2538_rf_driver = {
init,
prepare,
transmit,
send,
read,
channel_clear,
receiving_packet,
pending_packet,
on,
off,
};
/*---------------------------------------------------------------------------*/
/**
* \brief Implementation of the cc2538 RF driver process
*
* This process is started by init(). It simply sits there waiting for
* an event. Upon frame reception, the RX ISR will poll this process.
* Subsequently, the contiki core will generate an event which will
* call this process so that the received frame can be picked up from
* the RF RX FIFO
*
*/
PROCESS_THREAD(cc2538_rf_process, ev, data)
{
int len;
PROCESS_BEGIN();
while(1) {
PROCESS_YIELD_UNTIL(ev == PROCESS_EVENT_POLL);
packetbuf_clear();
len = read(packetbuf_dataptr(), PACKETBUF_SIZE);
if(len > 0) {
packetbuf_set_datalen(len);
NETSTACK_RDC.input();
}
/* If we were polled due to an RF error, reset the transceiver */
if(rf_flags & RF_MUST_RESET) {
rf_flags = 0;
off();
init();
}
}
PROCESS_END();
}
/*---------------------------------------------------------------------------*/
/**
* \brief The cc2538 RF RX/TX ISR
*
* This is the interrupt service routine for all RF interrupts relating
* to RX and TX. Error conditions are handled by cc2538_rf_err_isr().
* Currently, we only acknowledge the FIFOP interrupt source.
*/
void
cc2538_rf_rx_tx_isr(void)
{
ENERGEST_ON(ENERGEST_TYPE_IRQ);
process_poll(&cc2538_rf_process);
/* We only acknowledge FIFOP so we can safely wipe out the entire SFR */
REG(RFCORE_SFR_RFIRQF0) = 0;
ENERGEST_OFF(ENERGEST_TYPE_IRQ);
}
/*---------------------------------------------------------------------------*/
/**
* \brief The cc2538 RF Error ISR
*
* This is the interrupt service routine for all RF errors. We
* acknowledge every error type and instead of trying to be smart and
* act differently depending on error condition, we simply reset the
* transceiver. RX FIFO overflow is an exception, we ignore this error
* since read() handles it anyway.
*
* However, we don't want to reset within this ISR. If the error occurs
* while we are reading a frame out of the FIFO, trashing the FIFO in
* the middle of read(), would result in further errors (RX underflows).
*
* Instead, we set a flag and poll the driver process. The process will
* reset the transceiver without any undesirable consequences.
*/
void
cc2538_rf_err_isr(void)
{
ENERGEST_ON(ENERGEST_TYPE_IRQ);
PRINTF("RF Error: 0x%08lx\n", REG(RFCORE_SFR_RFERRF));
/* If the error is not an RX FIFO overflow, set a flag */
if(REG(RFCORE_SFR_RFERRF) != RFCORE_SFR_RFERRF_RXOVERF) {
rf_flags |= RF_MUST_RESET;
}
REG(RFCORE_SFR_RFERRF) = 0;
process_poll(&cc2538_rf_process);
ENERGEST_OFF(ENERGEST_TYPE_IRQ);
}
/*---------------------------------------------------------------------------*/
/** @} */

176
cpu/cc2538/dev/cc2538-rf.h Normal file
View File

@ -0,0 +1,176 @@
/*
* 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 Institute nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
* SUCH DAMAGE.
*
* This file is part of the Contiki operating system.
*/
/**
* \addtogroup cc2538
* @{
*
* \defgroup cc2538-rf cc2538 RF Driver
*
* Driver implementation for the cc2538 RF transceiver
* @{
*
* \file
* Header file for the cc2538 RF driver
*/
#ifndef CC2538_RF_H__
#define CC2538_RF_H__
#include "contiki.h"
#include "dev/radio.h"
#include "dev/rfcore.h"
#include "reg.h"
/*---------------------------------------------------------------------------
* RF Config
*---------------------------------------------------------------------------*/
/* Constants */
#define CC2538_RF_CCA_THRES_USER_GUIDE 0xF8
#define CC2538_RF_TX_POWER_RECOMMENDED 0xD5 /* ToDo: Determine value */
#define CC2538_RF_CHANNEL_MIN 11
#define CC2538_RF_CHANNEL_MAX 26
#define CC2538_RF_CHANNEL_SPACING 5
#define CC2538_RF_MAX_PACKET_LEN 127
#define CC2538_RF_MIN_PACKET_LEN 4
#define CC2538_RF_CCA_CLEAR 1
#define CC2538_RF_CCA_BUSY 0
/*---------------------------------------------------------------------------*/
#ifdef CC2538_RF_CONF_TX_POWER
#define CC2538_RF_TX_POWER CC2538_RF_CONF_TX_POWER
#else
#define CC2538_RF_TX_POWER CC2538_RF_TX_POWER_RECOMMENDED
#endif /* CC2538_RF_CONF_TX_POWER */
#ifdef CC2538_RF_CONF_CCA_THRES
#define CC2538_RF_CCA_THRES CC2538_RF_CONF_CCA_THRES
#else
#define CC2538_RF_CCA_THRES CCA_THRES_USER_GUIDE /** User guide recommendation */
#endif /* CC2538_RF_CONF_CCA_THRES */
#ifdef CC2538_RF_CONF_CHANNEL
#define CC2538_RF_CHANNEL CC2538_RF_CONF_CHANNEL
#else
#define CC2538_RF_CHANNEL 18
#endif /* CC2538_RF_CONF_CHANNEL */
#ifdef CC2538_RF_CONF_AUTOACK
#define CC2538_RF_AUTOACK CC2538_RF_CONF_AUTOACK
#else
#define CC2538_RF_AUTOACK 1
#endif /* CC2538_RF_CONF_AUTOACK */
/*---------------------------------------------------------------------------
* Command Strobe Processor
*---------------------------------------------------------------------------*/
/* OPCODES */
#define CC2538_RF_CSP_OP_ISRXON 0xE3
#define CC2538_RF_CSP_OP_ISTXON 0xE9
#define CC2538_RF_CSP_OP_ISTXONCCA 0xEA
#define CC2538_RF_CSP_OP_ISRFOFF 0xEF
#define CC2538_RF_CSP_OP_ISFLUSHRX 0xED
#define CC2538_RF_CSP_OP_ISFLUSHTX 0xEE
/**
* \brief Send an RX ON command strobe to the CSP
*/
#define CC2538_RF_CSP_ISRXON() \
do { REG(RFCORE_SFR_RFST) = CC2538_RF_CSP_OP_ISRXON; } while(0)
/**
* \brief Send a TX ON command strobe to the CSP
*/
#define CC2538_RF_CSP_ISTXON() \
do { REG(RFCORE_SFR_RFST) = CC2538_RF_CSP_OP_ISTXON; } while(0)
/**
* \brief Send a RF OFF command strobe to the CSP
*/
#define CC2538_RF_CSP_ISRFOFF() \
do { REG(RFCORE_SFR_RFST) = CC2538_RF_CSP_OP_ISRFOFF; } while(0)
/**
* \brief Flush the RX FIFO
*/
#define CC2538_RF_CSP_ISFLUSHRX() do { \
REG(RFCORE_SFR_RFST) = CC2538_RF_CSP_OP_ISFLUSHRX; \
REG(RFCORE_SFR_RFST) = CC2538_RF_CSP_OP_ISFLUSHRX; \
} while(0)
/**
* \brief Flush the TX FIFO
*/
#define CC2538_RF_CSP_ISFLUSHTX() do { \
REG(RFCORE_SFR_RFST) = CC2538_RF_CSP_OP_ISFLUSHTX; \
REG(RFCORE_SFR_RFST) = CC2538_RF_CSP_OP_ISFLUSHTX; \
} while(0)
/*---------------------------------------------------------------------------*/
/** The NETSTACK data structure for the cc2538 RF driver */
extern const struct radio_driver cc2538_rf_driver;
/*---------------------------------------------------------------------------*/
/**
* \brief Set the current operating channel
* \param channel The desired channel as a value in [11,26]
* \return Returns a value in [11,26] representing the current channel
* or a negative value if \e channel was out of bounds
*/
int8_t cc2538_rf_channel_set(uint8_t channel);
/**
* \brief Get the current operating channel
* \return Returns a value in [11,26] representing the current channel
*/
uint8_t cc2538_rf_channel_get();
/**
* \brief Sets RF TX power
* \param new_power The desired power level
* \return The power level in use after the adjustment
*
* The value specified in \e new_power will be written directly to the
* RFCORE_XREG_TXPOWER register. See the datasheet for more details on
* possible values.
*/
uint8_t cc2538_rf_power_set(uint8_t new_power);
/**
* \brief Sets addresses and PAN identifier to the relevant RF hardware
* registers
* \param pan The PAN Identifier
*
* Values for short and extended addresses are not needed as parameters
* since they exist in the rimeaddr buffer in the contiki core. They
* are thus simply copied over from there.
*/
void cc2538_rf_set_addr(uint16_t pan);
/*---------------------------------------------------------------------------*/
#endif /* CC2538_RF_H__ */
/**
* @}
* @}
*/

147
cpu/cc2538/dev/gpio.c Normal file
View File

@ -0,0 +1,147 @@
/*
* 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 cc2538-gpio
* @{
*
* \file
* Implementation of the cc2538 GPIO controller
*/
#include "contiki.h"
#include "sys/energest.h"
#include "dev/leds.h"
#include "dev/gpio.h"
#include "dev/nvic.h"
#include "reg.h"
#include "lpm.h"
#include <string.h>
/**
* \brief Pointer to a function to be called when a GPIO interrupt is detected.
* Callbacks for Port A, Pins[0:7] are stored in positions [0:7] of this
* buffer, Port B callbacks in [8:15] and so on
*/
static gpio_callback_t gpio_callbacks[32];
/*---------------------------------------------------------------------------*/
void
gpio_register_callback(gpio_callback_t f, uint8_t port, uint8_t pin)
{
gpio_callbacks[(port << 3) + pin] = f;
}
/*---------------------------------------------------------------------------*/
/** \brief Run through all registered GPIO callbacks and invoke those
* associated with the \a port and the pins specified by \a mask
* \param mask Search callbacks associated with pins specified by this mask
* \param port Search callbacks associated with this port. Here, port is
* specified as a number between 0 and 3. Port A: 0, Port B: 1 etc */
void
notify(uint8_t mask, uint8_t port)
{
uint8_t i;
gpio_callback_t *f = &gpio_callbacks[port << 3];
for(i = 0; i < 8; i++) {
if(mask & (1 << i)) {
if((*f) != NULL) {
(*f)(port, i);
}
}
f++;
}
}
/*---------------------------------------------------------------------------*/
/** \brief Interrupt service routine for Port A */
void
gpio_port_a_isr()
{
ENERGEST_ON(ENERGEST_TYPE_IRQ);
lpm_exit();
notify(REG(GPIO_A_BASE | GPIO_MIS), GPIO_A_NUM);
REG(GPIO_A_BASE | GPIO_IC) = 0xFF;
ENERGEST_OFF(ENERGEST_TYPE_IRQ);
}
/*---------------------------------------------------------------------------*/
/** \brief Interrupt service routine for Port B */
void
gpio_port_b_isr()
{
ENERGEST_ON(ENERGEST_TYPE_IRQ);
lpm_exit();
notify(REG(GPIO_B_BASE | GPIO_MIS), GPIO_B_NUM);
REG(GPIO_B_BASE | GPIO_IC) = 0xFF;
ENERGEST_OFF(ENERGEST_TYPE_IRQ);
}
/*---------------------------------------------------------------------------*/
/** \brief Interrupt service routine for Port C */
void
gpio_port_c_isr()
{
ENERGEST_ON(ENERGEST_TYPE_IRQ);
lpm_exit();
notify(REG(GPIO_C_BASE | GPIO_MIS), GPIO_C_NUM);
REG(GPIO_C_BASE | GPIO_IC) = 0xFF;
ENERGEST_OFF(ENERGEST_TYPE_IRQ);
}
/*---------------------------------------------------------------------------*/
/** \brief Interrupt service routine for Port D */
void
gpio_port_d_isr()
{
ENERGEST_ON(ENERGEST_TYPE_IRQ);
lpm_exit();
notify(REG(GPIO_D_BASE | GPIO_MIS), GPIO_D_NUM);
REG(GPIO_D_BASE | GPIO_IC) = 0xFF;
ENERGEST_OFF(ENERGEST_TYPE_IRQ);
}
/*---------------------------------------------------------------------------*/
void
gpio_init()
{
memset(gpio_callbacks, 0, sizeof(gpio_callbacks));
}
/** @} */

479
cpu/cc2538/dev/gpio.h Normal file
View File

@ -0,0 +1,479 @@
/*
* 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 cc2538
* @{
*
* \defgroup cc2538-gpio cc2538 General-Purpose I/O
*
* Driver for the cc2538 GPIO controller
* @{
*
* \file
* Header file with register and macro declarations for the cc2538 GPIO module
*/
#ifndef GPIO_H_
#define GPIO_H_
#include "reg.h"
#include <stdint.h>
/**
* \brief Type definition for callbacks invoked by the GPIO ISRs
* \param port The port that triggered the GPIO interrupt. \e port is passed
* by its numeric representation (Port A:0, B:1 etc). Defines for
* these numeric representations are GPIO_x_NUM
* \param pin The pin that triggered the interrupt, specified by number
* (0, 1, ..., 7)
*
* This is the prototype of a function pointer passed to
* gpio_register_callback(). These callbacks are registered on a port/pin
* basis. When a GPIO port generates an interrupt, if a callback has been
* registered for the port/pin combination, the ISR will invoke it. The ISR
* will pass the port/pin as arguments in that call, so that a developer can
* re-use the same callback for multiple port/pin combinations
*/
typedef void (* gpio_callback_t)(uint8_t port, uint8_t pin);
/*---------------------------------------------------------------------------*/
/** \name Base addresses for the GPIO register instances
* @{
*/
#define GPIO_A_BASE 0x400D9000 /**< GPIO_A */
#define GPIO_B_BASE 0x400DA000 /**< GPIO_B */
#define GPIO_C_BASE 0x400DB000 /**< GPIO_C */
#define GPIO_D_BASE 0x400DC000 /**< GPIO_D */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name Numeric representation of the four GPIO ports
* @{
*/
#define GPIO_A_NUM 0 /**< GPIO_A: 0 */
#define GPIO_B_NUM 1 /**< GPIO_B: 1 */
#define GPIO_C_NUM 2 /**< GPIO_C: 2 */
#define GPIO_D_NUM 3 /**< GPIO_D: 3 */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name GPIO Manipulation macros
* @{
*/
/** \brief Set pins with PIN_MASK of port with PORT_BASE to input.
* \param PORT_BASE GPIO Port register offset
* \param PIN_MASK Pin number mask. Pin 0: 0x01, Pin 1: 0x02 ... Pin 7: 0x80
*/
#define GPIO_SET_INPUT(PORT_BASE, PIN_MASK) \
do { REG(PORT_BASE | GPIO_DIR) &= ~PIN_MASK; } while(0)
/** \brief Set pins with PIN_MASK of port with PORT_BASE to output.
* \param PORT_BASE GPIO Port register offset
* \param PIN_MASK Pin number mask. Pin 0: 0x01, Pin 1: 0x02 ... Pin 7: 0x80
*/
#define GPIO_SET_OUTPUT(PORT_BASE, PIN_MASK) \
do { REG(PORT_BASE | GPIO_DIR) |= PIN_MASK; } while(0)
/** \brief Set pins with PIN_MASK of port with PORT_BASE to detect edge.
* \param PORT_BASE GPIO Port register offset
* \param PIN_MASK Pin number mask. Pin 0: 0x01, Pin 1: 0x02 ... Pin 7: 0x80
*/
#define GPIO_DETECT_EDGE(PORT_BASE, PIN_MASK) \
do { REG(PORT_BASE | GPIO_IS) &= ~PIN_MASK; } while(0)
/** \brief Set pins with PIN_MASK of port with PORT_BASE to detect level.
* \param PORT_BASE GPIO Port register offset
* \param PIN_MASK Pin number mask. Pin 0: 0x01, Pin 1: 0x02 ... Pin 7: 0x80
*/
#define GPIO_DETECT_LEVEL(PORT_BASE, PIN_MASK) \
do { REG(PORT_BASE | GPIO_IS) |= PIN_MASK; } while(0)
/** \brief Set pins with PIN_MASK of port with PORT_BASE to trigger an
* interrupt on both edges.
* \param PORT_BASE GPIO Port register offset
* \param PIN_MASK Pin number mask. Pin 0: 0x01, Pin 1: 0x02 ... Pin 7: 0x80
*/
#define GPIO_TRIGGER_BOTH_EDGES(PORT_BASE, PIN_MASK) \
do { REG(PORT_BASE | GPIO_IBE) |= PIN_MASK; } while(0)
/** \brief Set pins with PIN_MASK of port with PORT_BASE to trigger an
* interrupt on single edge (controlled by GPIO_IEV).
* \param PORT_BASE GPIO Port register offset
* \param PIN_MASK Pin number mask. Pin 0: 0x01, Pin 1: 0x02 ... Pin 7: 0x80
*/
#define GPIO_TRIGGER_SINGLE_EDGE(PORT_BASE, PIN_MASK) \
do { REG(PORT_BASE | GPIO_IBE) &= ~PIN_MASK; } while(0)
/** \brief Set pins with PIN_MASK of port with PORT_BASE to trigger an
* interrupt on rising edge.
* \param PORT_BASE GPIO Port register offset
* \param PIN_MASK Pin number mask. Pin 0: 0x01, Pin 1: 0x02 ... Pin 7: 0x80
*/
#define GPIO_DETECT_RISING(PORT_BASE, PIN_MASK) \
do { REG(PORT_BASE | GPIO_IEV) |= PIN_MASK; } while(0)
/** \brief Set pins with PIN_MASK of port with PORT_BASE to trigger an
* interrupt on falling edge.
* \param PORT_BASE GPIO Port register offset
* \param PIN_MASK Pin number mask. Pin 0: 0x01, Pin 1: 0x02 ... Pin 7: 0x80
*/
#define GPIO_DETECT_FALLING(PORT_BASE, PIN_MASK) \
do { REG(PORT_BASE | GPIO_IEV) &= ~PIN_MASK; } while(0)
/** \brief Enable interrupt triggering for pins with PIN_MASK of port with
* PORT_BASE.
* \param PORT_BASE GPIO Port register offset
* \param PIN_MASK Pin number mask. Pin 0: 0x01, Pin 1: 0x02 ... Pin 7: 0x80
*/
#define GPIO_ENABLE_INTERRUPT(PORT_BASE, PIN_MASK) \
do { REG(PORT_BASE | GPIO_IE) |= PIN_MASK; } while(0)
/** \brief Disable interrupt triggering for pins with PIN_MASK of port with
* PORT_BASE.
* \param PORT_BASE GPIO Port register offset
* \param PIN_MASK Pin number mask. Pin 0: 0x01, Pin 1: 0x02 ... Pin 7: 0x80
*/
#define GPIO_DISABLE_INTERRUPT(PORT_BASE, PIN_MASK) \
do { REG(PORT_BASE | GPIO_IE) &= ~PIN_MASK; } while(0)
/** \brief Enable interrupt triggering for pins with PIN_MASK of port with
* PORT_BASE.
* \param PORT_BASE GPIO Port register offset
* \param PIN_MASK Pin number mask. Pin 0: 0x01, Pin 1: 0x02 ... Pin 7: 0x80
*/
#define GPIO_PERIPHERAL_CONTROL(PORT_BASE, PIN_MASK) \
do { REG(PORT_BASE | GPIO_AFSEL) |= PIN_MASK; } while(0)
/** \brief Disable interrupt triggering for pins with PIN_MASK of port with
* PORT_BASE.
* \param PORT_BASE GPIO Port register offset
* \param PIN_MASK Pin number mask. Pin 0: 0x01, Pin 1: 0x02 ... Pin 7: 0x80
*/
#define GPIO_SOFTWARE_CONTROL(PORT_BASE, PIN_MASK) \
do { REG(PORT_BASE | GPIO_AFSEL) &= ~PIN_MASK; } while(0)
/**
* \brief Converts a pin number to a pin mask
* \param The pin number in the range [0..7]
* \return A pin mask which can be used as the PIN_MASK argument of the macros
* in this category
*/
#define GPIO_PIN_MASK(PIN) (1 << PIN)
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPIO Register offset declarations
* @{
*/
#define GPIO_DATA 0x00000000 /**< Data register */
#define GPIO_DIR 0x00000400 /**< Data direction register */
#define GPIO_IS 0x00000404 /**< Interrupt sense */
#define GPIO_IBE 0x00000408 /**< Interrupt both edges */
#define GPIO_IEV 0x0000040C /**< Interrupt event */
#define GPIO_IE 0x00000410 /**< Interrupt mask */
#define GPIO_RIS 0x00000414 /**< Interrupt status - raw */
#define GPIO_MIS 0x00000418 /**< Interrupt status - masked */
#define GPIO_IC 0x0000041C /**< Interrupt clear */
#define GPIO_AFSEL 0x00000420 /**< Mode control select */
#define GPIO_GPIOLOCK 0x00000520 /**< GPIO commit unlock */
#define GPIO_GPIOCR 0x00000524 /**< GPIO commit */
#define GPIO_PMUX 0x00000700 /**< PMUX register */
#define GPIO_P_EDGE_CTRL 0x00000704 /**< Port edge control */
#define GPIO_USB_CTRL 0x00000708 /**< USB input power-up edge ctrl */
#define GPIO_PI_IEN 0x00000710 /**< Power-up interrupt enable */
#define GPIO_IRQ_DETECT_ACK 0x00000718 /**< IRQ detect ACK - I/O ports */
#define GPIO_USB_IRQ_ACK 0x0000071C /**< IRQ detect ACK - USB */
#define GPIO_IRQ_DETECT_UNMASK 0x00000720 /**< IRQ detect ACK - masked */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPIO_DATA register bit masks
* @{
*/
#define GPIO_DATA_DATA 0x000000FF /**< Input and output data */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPIO_DIR register bit masks
* @{
*/
#define GPIO_DIR_DIR 0x000000FF /**< Pin Input (0) / Output (1) */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPIO_IS register bit masks
* @{
*/
#define GPIO_IS_IS 0x000000FF /**< Detect Edge (0) / Level (1) */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPIO_IBE register bit masks
* @{
*/
#define GPIO_IBE_IBE 0x000000FF /**< Both Edges (1) / Single (0) */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPIO_IEV register bit masks
* @{
*/
#define GPIO_IEV_IEV 0x000000FF /**< Rising (1) / Falling (0) */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPIO_IE register bit masks
* @{
*/
#define GPIO_IE_IE 0x000000FF /**< Masked (0) / Not Masked (1) */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPIO_RIS register bit masks
* @{
*/
#define GPIO_RIS_RIS 0x000000FF /**< Raw interrupt status */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPIO_MIS register bit masks
* @{
*/
#define GPIO_MIS_MIS 0x000000FF /**< Masked interrupt status */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPIO_IC register bit masks
* @{
*/
#define GPIO_IC_IC 0x000000FF /**< Clear edge detection (1) */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPIO_AFSEL register bit masks
* @{
*/
#define GPIO_AFSEL_AFSEL 0x000000FF /**< Software (0) / Peripheral (1) */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPIO_GPIOLOCK register bit masks
* @{
*/
#define GPIO_GPIOLOCK_LOCK 0xFFFFFFFF /**< Locked (1) / Unlocked (0) */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPIO_GPIOCR register bit masks
* @{
*/
#define GPIO_GPIOCR_CR 0x000000FF /**< Allow alternate function (1) */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPIO_PMUX register bit masks
* @{
*/
#define GPIO_PMUX_CKOEN 0x00000080 /**< Clock out enable */
#define GPIO_PMUX_CKOPIN 0x00000010 /**< Decouple control pin select */
#define GPIO_PMUX_DCEN 0x00000008 /**< Decouple control enable */
#define GPIO_PMUX_DCPIN 0x00000001 /**< Decouple control pin select */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPIO_P_EDGE_CTRL register bit masks.
* \brief Rising (0) / Falling (1)
* @{
*/
#define GPIO_P_EDGE_CTRL_PDIRC7 0x80000000 /**< Port D bit 7 */
#define GPIO_P_EDGE_CTRL_PDIRC6 0x40000000 /**< Port D bit 6 */
#define GPIO_P_EDGE_CTRL_PDIRC5 0x20000000 /**< Port D bit 5 */
#define GPIO_P_EDGE_CTRL_PDIRC4 0x10000000 /**< Port D bit 4 */
#define GPIO_P_EDGE_CTRL_PDIRC3 0x08000000 /**< Port D bit 3 */
#define GPIO_P_EDGE_CTRL_PDIRC2 0x04000000 /**< Port D bit 2 */
#define GPIO_P_EDGE_CTRL_PDIRC1 0x02000000 /**< Port D bit 1 */
#define GPIO_P_EDGE_CTRL_PDIRC0 0x01000000 /**< Port D bit 0 */
#define GPIO_P_EDGE_CTRL_PCIRC7 0x00800000 /**< Port C bit 7 */
#define GPIO_P_EDGE_CTRL_PCIRC6 0x00400000 /**< Port C bit 6 */
#define GPIO_P_EDGE_CTRL_PCIRC5 0x00200000 /**< Port C bit 5 */
#define GPIO_P_EDGE_CTRL_PCIRC4 0x00100000 /**< Port C bit 4 */
#define GPIO_P_EDGE_CTRL_PCIRC3 0x00080000 /**< Port C bit 3 */
#define GPIO_P_EDGE_CTRL_PCIRC2 0x00040000 /**< Port C bit 2 */
#define GPIO_P_EDGE_CTRL_PCIRC1 0x00020000 /**< Port C bit 1 */
#define GPIO_P_EDGE_CTRL_PCIRC0 0x00010000 /**< Port C bit 0 */
#define GPIO_P_EDGE_CTRL_PBIRC7 0x00008000 /**< Port B bit 7 */
#define GPIO_P_EDGE_CTRL_PBIRC6 0x00004000 /**< Port B bit 6 */
#define GPIO_P_EDGE_CTRL_PBIRC5 0x00002000 /**< Port B bit 5 */
#define GPIO_P_EDGE_CTRL_PBIRC4 0x00001000 /**< Port B bit 4 */
#define GPIO_P_EDGE_CTRL_PBIRC3 0x00000800 /**< Port B bit 3 */
#define GPIO_P_EDGE_CTRL_PBIRC2 0x00000400 /**< Port B bit 2 */
#define GPIO_P_EDGE_CTRL_PBIRC1 0x00000200 /**< Port B bit 1 */
#define GPIO_P_EDGE_CTRL_PBIRC0 0x00000100 /**< Port B bit 0 */
#define GPIO_P_EDGE_CTRL_PAIRC7 0x00000080 /**< Port A bit 7 */
#define GPIO_P_EDGE_CTRL_PAIRC6 0x00000040 /**< Port A bit 6 */
#define GPIO_P_EDGE_CTRL_PAIRC5 0x00000020 /**< Port A bit 5 */
#define GPIO_P_EDGE_CTRL_PAIRC4 0x00000010 /**< Port A bit 4 */
#define GPIO_P_EDGE_CTRL_PAIRC3 0x00000008 /**< Port A bit 3 */
#define GPIO_P_EDGE_CTRL_PAIRC2 0x00000004 /**< Port A bit 2 */
#define GPIO_P_EDGE_CTRL_PAIRC1 0x00000002 /**< Port A bit 1 */
#define GPIO_P_EDGE_CTRL_PAIRC0 0x00000001 /**< Port A bit 0 */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPIO_USB_CTRL register bit masks
* @{
*/
#define GPIO_USB_CTRL_USB_EDGE_CTL 0x00000001 /**< Rising (0) / Falling (1) */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPIO_PI_IEN register bit masks.
* \brief Enabled (1) / Disabled (0)
* @{
*/
#define GPIO_PI_IEN_PDIEN7 0x80000000 /**< Port D bit 7 */
#define GPIO_PI_IEN_PDIEN6 0x40000000 /**< Port D bit 6 */
#define GPIO_PI_IEN_PDIEN5 0x20000000 /**< Port D bit 5 */
#define GPIO_PI_IEN_PDIEN4 0x10000000 /**< Port D bit 4 */
#define GPIO_PI_IEN_PDIEN3 0x08000000 /**< Port D bit 3 */
#define GPIO_PI_IEN_PDIEN2 0x04000000 /**< Port D bit 2 */
#define GPIO_PI_IEN_PDIEN1 0x02000000 /**< Port D bit 1 */
#define GPIO_PI_IEN_PDIEN0 0x01000000 /**< Port D bit 0 */
#define GPIO_PI_IEN_PCIEN7 0x00800000 /**< Port C bit 7 */
#define GPIO_PI_IEN_PCIEN6 0x00400000 /**< Port C bit 6 */
#define GPIO_PI_IEN_PCIEN5 0x00200000 /**< Port C bit 5 */
#define GPIO_PI_IEN_PCIEN4 0x00100000 /**< Port C bit 4 */
#define GPIO_PI_IEN_PCIEN3 0x00080000 /**< Port C bit 3 */
#define GPIO_PI_IEN_PCIEN2 0x00040000 /**< Port C bit 2 */
#define GPIO_PI_IEN_PCIEN1 0x00020000 /**< Port C bit 1 */
#define GPIO_PI_IEN_PCIEN0 0x00010000 /**< Port C bit 0 */
#define GPIO_PI_IEN_PBIEN7 0x00008000 /**< Port B bit 7 */
#define GPIO_PI_IEN_PBIEN6 0x00004000 /**< Port B bit 6 */
#define GPIO_PI_IEN_PBIEN5 0x00002000 /**< Port B bit 5 */
#define GPIO_PI_IEN_PBIEN4 0x00001000 /**< Port B bit 4 */
#define GPIO_PI_IEN_PBIEN3 0x00000800 /**< Port B bit 3 */
#define GPIO_PI_IEN_PBIEN2 0x00000400 /**< Port B bit 2 */
#define GPIO_PI_IEN_PBIEN1 0x00000200 /**< Port B bit 1 */
#define GPIO_PI_IEN_PBIEN0 0x00000100 /**< Port B bit 0 */
#define GPIO_PI_IEN_PAIEN7 0x00000080 /**< Port A bit 7 */
#define GPIO_PI_IEN_PAIEN6 0x00000040 /**< Port A bit 6 */
#define GPIO_PI_IEN_PAIEN5 0x00000020 /**< Port A bit 5 */
#define GPIO_PI_IEN_PAIEN4 0x00000010 /**< Port A bit 4 */
#define GPIO_PI_IEN_PAIEN3 0x00000008 /**< Port A bit 3 */
#define GPIO_PI_IEN_PAIEN2 0x00000004 /**< Port A bit 2 */
#define GPIO_PI_IEN_PAIEN1 0x00000002 /**< Port A bit 1 */
#define GPIO_PI_IEN_PAIEN0 0x00000001 /**< Port A bit 0 */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPIO_IRQ_DETECT_ACK register bit masks
* \brief Detected (1) / Undetected (0)
* @{
*/
#define GPIO_IRQ_DETECT_ACK_PDIACK7 0x80000000 /**< Port D bit 7 */
#define GPIO_IRQ_DETECT_ACK_PDIACK6 0x40000000 /**< Port D bit 6 */
#define GPIO_IRQ_DETECT_ACK_PDIACK5 0x20000000 /**< Port D bit 5 */
#define GPIO_IRQ_DETECT_ACK_PDIACK4 0x10000000 /**< Port D bit 4 */
#define GPIO_IRQ_DETECT_ACK_PDIACK3 0x08000000 /**< Port D bit 3 */
#define GPIO_IRQ_DETECT_ACK_PDIACK2 0x04000000 /**< Port D bit 2 */
#define GPIO_IRQ_DETECT_ACK_PDIACK1 0x02000000 /**< Port D bit 1 */
#define GPIO_IRQ_DETECT_ACK_PDIACK0 0x01000000 /**< Port D bit 0 */
#define GPIO_IRQ_DETECT_ACK_PCIACK7 0x00800000 /**< Port C bit 7 */
#define GPIO_IRQ_DETECT_ACK_PCIACK6 0x00400000 /**< Port C bit 6 */
#define GPIO_IRQ_DETECT_ACK_PCIACK5 0x00200000 /**< Port C bit 5 */
#define GPIO_IRQ_DETECT_ACK_PCIACK4 0x00100000 /**< Port C bit 4 */
#define GPIO_IRQ_DETECT_ACK_PCIACK3 0x00080000 /**< Port C bit 3 */
#define GPIO_IRQ_DETECT_ACK_PCIACK2 0x00040000 /**< Port C bit 2 */
#define GPIO_IRQ_DETECT_ACK_PCIACK1 0x00020000 /**< Port C bit 1 */
#define GPIO_IRQ_DETECT_ACK_PCIACK0 0x00010000 /**< Port C bit 0 */
#define GPIO_IRQ_DETECT_ACK_PBIACK7 0x00008000 /**< Port B bit 7 */
#define GPIO_IRQ_DETECT_ACK_PBIACK6 0x00004000 /**< Port B bit 6 */
#define GPIO_IRQ_DETECT_ACK_PBIACK5 0x00002000 /**< Port B bit 5 */
#define GPIO_IRQ_DETECT_ACK_PBIACK4 0x00001000 /**< Port B bit 4 */
#define GPIO_IRQ_DETECT_ACK_PBIACK3 0x00000800 /**< Port B bit 3 */
#define GPIO_IRQ_DETECT_ACK_PBIACK2 0x00000400 /**< Port B bit 2 */
#define GPIO_IRQ_DETECT_ACK_PBIACK1 0x00000200 /**< Port B bit 1 */
#define GPIO_IRQ_DETECT_ACK_PBIACK0 0x00000100 /**< Port B bit 0 */
#define GPIO_IRQ_DETECT_ACK_PAIACK7 0x00000080 /**< Port A bit 7 */
#define GPIO_IRQ_DETECT_ACK_PAIACK6 0x00000040 /**< Port A bit 6 */
#define GPIO_IRQ_DETECT_ACK_PAIACK5 0x00000020 /**< Port A bit 5 */
#define GPIO_IRQ_DETECT_ACK_PAIACK4 0x00000010 /**< Port A bit 4 */
#define GPIO_IRQ_DETECT_ACK_PAIACK3 0x00000008 /**< Port A bit 3 */
#define GPIO_IRQ_DETECT_ACK_PAIACK2 0x00000004 /**< Port A bit 2 */
#define GPIO_IRQ_DETECT_ACK_PAIACK1 0x00000002 /**< Port A bit 1 */
#define GPIO_IRQ_DETECT_ACK_PAIACK0 0x00000001 /**< Port A bit 0 */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPIO_USB_IRQ_ACK register bit masks
* @{
*/
#define GPIO_USB_IRQ_ACK_USBACK 0x00000001 /**< Detected (1) / Not detected (0) */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPIO_IRQ_DETECT_UNMASK register bit masks.
* \brief Detected (1) / Not detected (0)
* @{
*/
#define GPIO_IRQ_DETECT_UNMASK_PDIACK7 0x80000000 /**< Port D bit 7 */
#define GPIO_IRQ_DETECT_UNMASK_PDIACK6 0x40000000 /**< Port D bit 6 */
#define GPIO_IRQ_DETECT_UNMASK_PDIACK5 0x20000000 /**< Port D bit 5 */
#define GPIO_IRQ_DETECT_UNMASK_PDIACK4 0x10000000 /**< Port D bit 4 */
#define GPIO_IRQ_DETECT_UNMASK_PDIACK3 0x08000000 /**< Port D bit 3 */
#define GPIO_IRQ_DETECT_UNMASK_PDIACK2 0x04000000 /**< Port D bit 2 */
#define GPIO_IRQ_DETECT_UNMASK_PDIACK1 0x02000000 /**< Port D bit 1 */
#define GPIO_IRQ_DETECT_UNMASK_PDIACK0 0x01000000 /**< Port D bit 0 */
#define GPIO_IRQ_DETECT_UNMASK_PCIACK7 0x00800000 /**< Port C bit 7 */
#define GPIO_IRQ_DETECT_UNMASK_PCIACK6 0x00400000 /**< Port C bit 6 */
#define GPIO_IRQ_DETECT_UNMASK_PCIACK5 0x00200000 /**< Port C bit 5 */
#define GPIO_IRQ_DETECT_UNMASK_PCIACK4 0x00100000 /**< Port C bit 4 */
#define GPIO_IRQ_DETECT_UNMASK_PCIACK3 0x00080000 /**< Port C bit 3 */
#define GPIO_IRQ_DETECT_UNMASK_PCIACK2 0x00040000 /**< Port C bit 2 */
#define GPIO_IRQ_DETECT_UNMASK_PCIACK1 0x00020000 /**< Port C bit 1 */
#define GPIO_IRQ_DETECT_UNMASK_PCIACK0 0x00010000 /**< Port C bit 0 */
#define GPIO_IRQ_DETECT_UNMASK_PBIACK7 0x00008000 /**< Port B bit 7 */
#define GPIO_IRQ_DETECT_UNMASK_PBIACK6 0x00004000 /**< Port B bit 6 */
#define GPIO_IRQ_DETECT_UNMASK_PBIACK5 0x00002000 /**< Port B bit 5 */
#define GPIO_IRQ_DETECT_UNMASK_PBIACK4 0x00001000 /**< Port B bit 4 */
#define GPIO_IRQ_DETECT_UNMASK_PBIACK3 0x00000800 /**< Port B bit 3 */
#define GPIO_IRQ_DETECT_UNMASK_PBIACK2 0x00000400 /**< Port B bit 2 */
#define GPIO_IRQ_DETECT_UNMASK_PBIACK1 0x00000200 /**< Port B bit 1 */
#define GPIO_IRQ_DETECT_UNMASK_PBIACK0 0x00000100 /**< Port B bit 0 */
#define GPIO_IRQ_DETECT_UNMASK_PAIACK7 0x00000080 /**< Port A bit 7 */
#define GPIO_IRQ_DETECT_UNMASK_PAIACK6 0x00000040 /**< Port A bit 6 */
#define GPIO_IRQ_DETECT_UNMASK_PAIACK5 0x00000020 /**< Port A bit 5 */
#define GPIO_IRQ_DETECT_UNMASK_PAIACK4 0x00000010 /**< Port A bit 4 */
#define GPIO_IRQ_DETECT_UNMASK_PAIACK3 0x00000008 /**< Port A bit 3 */
#define GPIO_IRQ_DETECT_UNMASK_PAIACK2 0x00000004 /**< Port A bit 2 */
#define GPIO_IRQ_DETECT_UNMASK_PAIACK1 0x00000002 /**< Port A bit 1 */
#define GPIO_IRQ_DETECT_UNMASK_PAIACK0 0x00000001 /**< Port A bit 0 */
/** @} */
/*---------------------------------------------------------------------------*/
/** \brief Initialise the GPIO module */
void gpio_init();
/**
* \brief Register GPIO callback
* \param f Pointer to a function to be called when \a pin of \a port
* generates an interrupt
* \param port Associate \a f with this port. \e port must be specified with
* its numeric representation (Port A:0, B:1 etc). Defines for these
* numeric representations are GPIO_x_NUM
* \param pin Associate \a f with this pin, which is specified by number
* (0, 1, ..., 7)
*/
void gpio_register_callback(gpio_callback_t f, uint8_t port, uint8_t pin);
#endif /* GPIO_H_ */
/**
* @}
* @}
*/

335
cpu/cc2538/dev/gptimer.h Normal file
View File

@ -0,0 +1,335 @@
/*
* 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 cc2538
* @{
*
* \defgroup cc2538-gptimer cc2538 General-Purpose Timers
*
* Driver for the cc2538 General Purpose Timers
* @{
*
* \file
* Header file for the cc2538 General Purpose Timers
*/
#ifndef GPTIMER_H_
#define GPTIMER_H_
/*---------------------------------------------------------------------------*/
/** \name Base addresses for the GPT register instances
* @{
*/
#define GPT_0_BASE 0x40030000 /**< GPTIMER0 */
#define GPT_1_BASE 0x40031000 /**< GPTIMER1 */
#define GPT_2_BASE 0x40032000 /**< GPTIMER2 */
#define GPT_3_BASE 0x40033000 /**< GPTIMER3 */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER Register offset declarations
* @{
*/
#define GPTIMER_CFG 0x00000000 /**< GPTM configuration */
#define GPTIMER_TAMR 0x00000004 /**< GPTM Timer A mode */
#define GPTIMER_TBMR 0x00000008 /**< GPTM Timer B mode */
#define GPTIMER_CTL 0x0000000C /**< GPTM control */
#define GPTIMER_SYNC 0x00000010 /**< GPTM synchronize (0 only) */
#define GPTIMER_IMR 0x00000018 /**< GPTM interrupt mask */
#define GPTIMER_RIS 0x0000001C /**< GPTM raw interrupt status */
#define GPTIMER_MIS 0x00000020 /**< GPTM masked interrupt status */
#define GPTIMER_ICR 0x00000024 /**< GPTM interrupt clear */
#define GPTIMER_TAILR 0x00000028 /**< GPTM Timer A interval load */
#define GPTIMER_TBILR 0x0000002C /**< GPTM Timer B interval load */
#define GPTIMER_TAMATCHR 0x00000030 /**< GPTM Timer A match */
#define GPTIMER_TBMATCHR 0x00000034 /**< GPTM Timer B match */
#define GPTIMER_TAPR 0x00000038 /**< GPTM Timer A prescale */
#define GPTIMER_TBPR 0x0000003C /**< GPTM Timer B prescale */
#define GPTIMER_TAPMR 0x00000040 /**< GPTM Timer A prescale match */
#define GPTIMER_TBPMR 0x00000044 /**< GPTM Timer B prescale match */
#define GPTIMER_TAR 0x00000048 /**< GPTM Timer A */
#define GPTIMER_TBR 0x0000004C /**< GPTM Timer B */
#define GPTIMER_TAV 0x00000050 /**< GPTM Timer A value */
#define GPTIMER_TBV 0x00000054 /**< GPTM Timer B value */
#define GPTIMER_RTCPD 0x00000058 /**< GPTM RTC predivide */
#define GPTIMER_TAPS 0x0000005C /**< GPTM Timer A prescale snapshot */
#define GPTIMER_TBPS 0x00000060 /**< GPTM Timer B prescale snapshot */
#define GPTIMER_TAPV 0x00000064 /**< GPTM Timer A prescale value */
#define GPTIMER_TBPV 0x00000068 /**< GPTM Timer B prescale value */
#define GPTIMER_PP 0x00000FC0 /**< GPTM peripheral properties */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_CFG register bit masks
* @{
*/
#define GPTIMER_CFG_GPTMCFG 0x00000007 /**< configuration */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_TnMR bit values
* @{
*/
#define GPTIMER_TAMR_TAMR_ONE_SHOT 0x00000001
#define GPTIMER_TAMR_TAMR_PERIODIC 0x00000002
#define GPTIMER_TAMR_TAMR_CAPTURE 0x00000003
#define GPTIMER_TBMR_TBMR_ONE_SHOT 0x00000001
#define GPTIMER_TBMR_TBMR_PERIODIC 0x00000002
#define GPTIMER_TBMR_TBMR_CAPTURE 0x00000003
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_TAMR register bit masks
* @{
*/
#define GPTIMER_TAMR_TAPLO 0x00000800 /**< Legacy PWM operation */
#define GPTIMER_TAMR_TAMRSU 0x00000400 /**< Timer A match register update mode */
#define GPTIMER_TAMR_TAPWMIE 0x00000200 /**< Timer A PWM interrupt enable */
#define GPTIMER_TAMR_TAILD 0x00000100 /**< Timer A PWM interval load write */
#define GPTIMER_TAMR_TASNAPS 0x00000080 /**< Timer A snap-shot mode */
#define GPTIMER_TAMR_TAWOT 0x00000040 /**< Timer A wait-on-trigger */
#define GPTIMER_TAMR_TAMIE 0x00000020 /**< Timer A match interrupt enable */
#define GPTIMER_TAMR_TACDIR 0x00000010 /**< Timer A count direction */
#define GPTIMER_TAMR_TAAMS 0x00000008 /**< Timer A alternate mode */
#define GPTIMER_TAMR_TACMR 0x00000004 /**< Timer A capture mode */
#define GPTIMER_TAMR_TAMR 0x00000003 /**< Timer A mode */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_TBMR register bit masks
* @{
*/
#define GPTIMER_TBMR_TBPLO 0x00000800 /**< Legacy PWM operation */
#define GPTIMER_TBMR_TBMRSU 0x00000400 /**< Timer B match register update mode */
#define GPTIMER_TBMR_TBPWMIE 0x00000200 /**< Timer B PWM interrupt enable */
#define GPTIMER_TBMR_TBILD 0x00000100 /**< Timer B PWM interval load write */
#define GPTIMER_TBMR_TBSNAPS 0x00000080 /**< Timer B snap-shot mode */
#define GPTIMER_TBMR_TBWOT 0x00000040 /**< Timer B wait-on-trigger */
#define GPTIMER_TBMR_TBMIE 0x00000020 /**< Timer B match interrupt enable */
#define GPTIMER_TBMR_TBCDIR 0x00000010 /**< Timer B count direction */
#define GPTIMER_TBMR_TBAMS 0x00000008 /**< Timer B alternate mode */
#define GPTIMER_TBMR_TBCMR 0x00000004 /**< Timer B capture mode */
#define GPTIMER_TBMR_TBMR 0x00000003 /**< Timer B mode */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_CTL register bit masks
* @{
*/
#define GPTIMER_CTL_TBPWML 0x00004000 /**< Timer B PWM output level */
#define GPTIMER_CTL_TBOTE 0x00002000 /**< Timer B output trigger enable */
#define GPTIMER_CTL_TBEVENT 0x00000C00 /**< Timer B event mode */
#define GPTIMER_CTL_TBSTALL 0x00000200 /**< Timer B stall enable */
#define GPTIMER_CTL_TBEN 0x00000100 /**< Timer B enable */
#define GPTIMER_CTL_TAPWML 0x00000040 /**< Timer A PWM output level */
#define GPTIMER_CTL_TAOTE 0x00000020 /**< Timer A output trigger enable */
#define GPTIMER_CTL_RTCEN 0x00000010 /**< RTC enable */
#define GPTIMER_CTL_TAEVENT 0x0000000C /**< Timer A event mode */
#define GPTIMER_CTL_TASTALL 0x00000002 /**< Timer A stall enable */
#define GPTIMER_CTL_TAEN 0x00000001 /**< Timer A enable */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_SYNC register bit masks
* @{
*/
#define GPTIMER_SYNC_SYNC3 0x000000C0 /**< Synchronize GPTM3 */
#define GPTIMER_SYNC_SYNC2 0x00000030 /**< Synchronize GPTM2 */
#define GPTIMER_SYNC_SYNC1 0x0000000C /**< Synchronize GPTM1 */
#define GPTIMER_SYNC_SYNC0 0x00000003 /**< Synchronize GPTM0 */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_IMR register bit masks
* @{
*/
#define GPTIMER_IMR_TBMIM 0x00000800 /**< Timer B match int mask */
#define GPTIMER_IMR_CBEIM 0x00000400 /**< Timer B capture event int mask */
#define GPTIMER_IMR_CBMIM 0x00000200 /**< Timer B capture match int mask */
#define GPTIMER_IMR_TBTOIM 0x00000100 /**< Timer B time-out int mask */
#define GPTIMER_IMR_TAMIM 0x00000010 /**< Timer A match int mask */
#define GPTIMER_IMR_RTCIM 0x00000008 /**< RTC int mask */
#define GPTIMER_IMR_CAEIM 0x00000004 /**< Timer A capture event int mask */
#define GPTIMER_IMR_CAMIM 0x00000002 /**< Timer A capture match int mask */
#define GPTIMER_IMR_TATOIM 0x00000001 /**< Timer A time-out int mask */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_RIS register bit masks
* @{
*/
#define GPTIMER_RIS_TBMRIS 0x00000800 /**< Timer B match raw status */
#define GPTIMER_RIS_CBERIS 0x00000400 /**< Timer B capture event raw status */
#define GPTIMER_RIS_CBMRIS 0x00000200 /**< Timer B capture match raw status */
#define GPTIMER_RIS_TBTORIS 0x00000100 /**< Timer B time-out raw status */
#define GPTIMER_RIS_TAMRIS 0x00000010 /**< Timer A match raw status */
#define GPTIMER_RIS_RTCRIS 0x00000008 /**< RTC raw status */
#define GPTIMER_RIS_CAERIS 0x00000004 /**< Timer A capture event raw status */
#define GPTIMER_RIS_CAMRIS 0x00000002 /**< Timer A capture match raw status */
#define GPTIMER_RIS_TATORIS 0x00000001 /**< Timer A time-out raw status */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_MIS register bit masks
* @{
*/
#define GPTIMER_MIS_TBMMIS 0x00000800 /**< Timer B match masked status */
#define GPTIMER_MIS_CBEMIS 0x00000400 /**< Timer B capture event masked status */
#define GPTIMER_MIS_CBMMIS 0x00000200 /**< Timer B capture match masked status */
#define GPTIMER_MIS_TBTOMIS 0x00000100 /**< Timer B time-out masked status */
#define GPTIMER_MIS_TAMRIS 0x00000010 /**< Timer A match masked status */
#define GPTIMER_MIS_RTCMIS 0x00000008 /**< RTC masked status */
#define GPTIMER_MIS_CAEMIS 0x00000004 /**< Timer A capture event masked status */
#define GPTIMER_MIS_CAMMIS 0x00000002 /**< Timer A capture match masked status */
#define GPTIMER_MIS_TATOMIS 0x00000001 /**< Timer A time-out masked status */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_ICR register bit masks
* @{
*/
#define GPTIMER_ICR_WUECINT 0x00010000 /**< write update error int clear */
#define GPTIMER_ICR_TBMCINT 0x00000800 /**< Timer B match int clear */
#define GPTIMER_ICR_CBECINT 0x00000400 /**< Timer B capture event int clear */
#define GPTIMER_ICR_CBMCINT 0x00000200 /**< Timer B capture match int clear */
#define GPTIMER_ICR_TBTOCINT 0x00000100 /**< Timer B time-out int clear */
#define GPTIMER_ICR_TAMCINT 0x00000010 /**< Timer A match int clear */
#define GPTIMER_ICR_RTCCINT 0x00000008 /**< RTC interrupt clear */
#define GPTIMER_ICR_CAECINT 0x00000004 /**< Timer A capture event int clear */
#define GPTIMER_ICR_CAMCINT 0x00000002 /**< Timer A capture match int clear */
#define GPTIMER_ICR_TATOCINT 0x00000001 /**< Timer A time-out int clear */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_TAILR register bit masks
* @{
*/
#define GPTIMER_TAILR_TAILR 0xFFFFFFFF /**< A interval load register */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_TBILR register bit masks
* @{
*/
#define GPTIMER_TBILR_TBILR 0x0000FFFF /**< B interval load register */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_TAMATCHR register bit masks
* @{
*/
#define GPTIMER_TAMATCHR_TAMR 0xFFFFFFFF /**< Timer A match register */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_TBMATCHR register bit masks
* @{
*/
#define GPTIMER_TBMATCHR_TBMR 0x0000FFFF /**< Timer B match register */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_TAPR register bit masks
* @{
*/
#define GPTIMER_TAPR_TAPSR 0x000000FF /**< Timer A prescale */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_TBPR register bit masks
* @{
*/
#define GPTIMER_TBPR_TBPSR 0x000000FF /**< Timer B prescale */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_TAPMR register bit masks
* @{
*/
#define GPTIMER_TAPMR_TAPSR 0x000000FF /**< Timer A prescale match */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_TBPMR register bit masks
* @{
*/
#define GPTIMER_TBPMR_TBPSR 0x000000FF /**< Timer B prescale match */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_TAR register bit masks
* @{
*/
#define GPTIMER_TAR_TAR 0xFFFFFFFF /**< Timer A register */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_TBR register bit masks
* @{
*/
#define GPTIMER_TBR_TBR 0x0000FFFF /**< Timer B register */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_TAV register bit masks
* @{
*/
#define GPTIMER_TAV_TAV 0xFFFFFFFF /**< Timer A register */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_TBV register bit masks
* @{
*/
#define GPTIMER_TBV_PRE 0x00FF0000 /**< Timer B prescale register */
#define GPTIMER_TBV_TBV 0x0000FFFF /**< Timer B register */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_RTCPD register bit masks
* @{
*/
#define GPTIMER_RTCPD_RTCPD 0x0000FFFF /**< RTC predivider */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_TAPS register bit masks
* @{
*/
#define GPTIMER_TAPS_PSS 0x0000FFFF /**< Timer A prescaler */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_TBPS register bit masks
* @{
*/
#define GPTIMER_TBPS_PSS 0x0000FFFF /**< Timer B prescaler */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_TAPV register bit masks
* @{
*/
#define GPTIMER_TAPV_PSV 0x0000FFFF /**< Timer A prescaler value */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_TBPV register bit masks
* @{
*/
#define GPTIMER_TBPV_PSV 0x0000FFFF /**< Timer B prescaler value */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name GPTIMER_PP register bit masks
* @{
*/
#define GPTIMER_PP_ALTCLK 0x00000040 /**< Alternate clock source */
#define GPTIMER_PP_SYNCNT 0x00000020 /**< Synchronized start */
#define GPTIMER_PP_CHAIN 0x00000010 /**< Chain with other timers */
#define GPTIMER_PP_SIZE 0x0000000F /**< Timer size */
/** @} */
#endif /* GPTIMER_H_ */
/**
* @}
* @}
*/

66
cpu/cc2538/dev/ioc.c Normal file
View File

@ -0,0 +1,66 @@
/*
* 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 cc2538-ioc
* @{
*
* \file
* Implementation of IOC functions
*/
#include "contiki.h"
#include "dev/ioc.h"
#include <stdint.h>
static uint32_t *ioc_over;
static uint32_t *ioc_sel;
/*---------------------------------------------------------------------------*/
void
ioc_init()
{
ioc_over = (uint32_t *)IOC_PA0_OVER;
ioc_sel = (uint32_t *)IOC_PA0_SEL;
}
/*---------------------------------------------------------------------------*/
void
ioc_set_over(uint8_t port, uint8_t pin, uint8_t over)
{
ioc_over[(port << 3) + pin] = over;
}
/*---------------------------------------------------------------------------*/
void
ioc_set_sel(uint8_t port, uint8_t pin, uint8_t sel)
{
ioc_sel[(port << 3) + pin] = sel;
}
/*---------------------------------------------------------------------------*/
/** @} */

278
cpu/cc2538/dev/ioc.h Normal file
View File

@ -0,0 +1,278 @@
/*
* 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 cc2538
* @{
*
* \defgroup cc2538-ioc cc2538 I/O Control
*
* cc2538 I/O Control Module
* @{
*
* \file
* Header file with declarations for the I/O Control module
*/
#ifndef IOC_H_
#define IOC_H_
#include <stdint.h>
/*---------------------------------------------------------------------------*/
/** \name IOC Signal Select Registers
* @{
*/
#define IOC_PA0_SEL 0x400D4000
#define IOC_PA1_SEL 0x400D4004
#define IOC_PA2_SEL 0x400D4008
#define IOC_PA3_SEL 0x400D400C
#define IOC_PA4_SEL 0x400D4010
#define IOC_PA5_SEL 0x400D4014
#define IOC_PA6_SEL 0x400D4018
#define IOC_PA7_SEL 0x400D401C
#define IOC_PB0_SEL 0x400D4020
#define IOC_PB1_SEL 0x400D4024
#define IOC_PB2_SEL 0x400D4028
#define IOC_PB3_SEL 0x400D402C
#define IOC_PB4_SEL 0x400D4030
#define IOC_PB5_SEL 0x400D4034
#define IOC_PB6_SEL 0x400D4038
#define IOC_PB7_SEL 0x400D403C
#define IOC_PC0_SEL 0x400D4040
#define IOC_PC1_SEL 0x400D4044
#define IOC_PC2_SEL 0x400D4048
#define IOC_PC3_SEL 0x400D404C
#define IOC_PC4_SEL 0x400D4050
#define IOC_PC5_SEL 0x400D4054
#define IOC_PC6_SEL 0x400D4058
#define IOC_PC7_SEL 0x400D405C
#define IOC_PD0_SEL 0x400D4060
#define IOC_PD1_SEL 0x400D4064
#define IOC_PD2_SEL 0x400D4068
#define IOC_PD3_SEL 0x400D406C
#define IOC_PD4_SEL 0x400D4070
#define IOC_PD5_SEL 0x400D4074
#define IOC_PD6_SEL 0x400D4078
#define IOC_PD7_SEL 0x400D407C
/** @} */
/*---------------------------------------------------------------------------*/
/** \name IOC Override Configuration Registers
* @{
*/
#define IOC_PA0_OVER 0x400D4080
#define IOC_PA1_OVER 0x400D4084
#define IOC_PA2_OVER 0x400D4088
#define IOC_PA3_OVER 0x400D408C
#define IOC_PA4_OVER 0x400D4090
#define IOC_PA5_OVER 0x400D4094
#define IOC_PA6_OVER 0x400D4098
#define IOC_PA7_OVER 0x400D409C
#define IOC_PB0_OVER 0x400D40A0
#define IOC_PB1_OVER 0x400D40A4
#define IOC_PB2_OVER 0x400D40A8
#define IOC_PB3_OVER 0x400D40AC
#define IOC_PB4_OVER 0x400D40B0
#define IOC_PB5_OVER 0x400D40B4
#define IOC_PB6_OVER 0x400D40B8
#define IOC_PB7_OVER 0x400D40BC
#define IOC_PC0_OVER 0x400D40C0
#define IOC_PC1_OVER 0x400D40C4
#define IOC_PC2_OVER 0x400D40C8
#define IOC_PC3_OVER 0x400D40CC
#define IOC_PC4_OVER 0x400D40D0
#define IOC_PC5_OVER 0x400D40D4
#define IOC_PC6_OVER 0x400D40D8
#define IOC_PC7_OVER 0x400D40DC
#define IOC_PD0_OVER 0x400D40E0
#define IOC_PD1_OVER 0x400D40E4
#define IOC_PD2_OVER 0x400D40E8
#define IOC_PD3_OVER 0x400D40EC
#define IOC_PD4_OVER 0x400D40F0
#define IOC_PD5_OVER 0x400D40F4
#define IOC_PD6_OVER 0x400D40F8
#define IOC_PD7_OVER 0x400D40FC
/** @} */
/*---------------------------------------------------------------------------*/
/** \name IOC Input Pin Select Registers
* @{
*/
#define IOC_UARTRXD_UART0 0x400D4100 /**< UART0 RX */
#define IOC_UARTCTS_UART1 0x400D4104 /**< UART1 CTS */
#define IOC_UARTRXD_UART1 0x400D4108 /**< UART1 RX */
#define IOC_CLK_SSI_SSI0 0x400D410C /**< SSI0 Clock */
#define IOC_SSIRXD_SSI0 0x400D4110 /**< SSI0 RX */
#define IOC_SSIFSSIN_SSI0 0x400D4114 /**< SSI0 FSSIN */
#define IOC_CLK_SSIIN_SSI0 0x400D4118 /**< SSI0 Clock SSIIN */
#define IOC_CLK_SSI_SSI1 0x400D411C /**< SSI1 Clock */
#define IOC_SSIRXD_SSI1 0x400D4120 /**< SSI1 RX */
#define IOC_SSIFSSIN_SSI1 0x400D4124 /**< SSI1 FSSIN Select */
#define IOC_CLK_SSIIN_SSI1 0x400D4128 /**< SSI1 Clock SSIIN */
#define IOC_I2CMSSDA 0x400D412C /**< I2C SDA */
#define IOC_I2CMSSCL 0x400D4130 /**< I2C SCL */
#define IOC_GPT0OCP1 0x400D4134 /**< GPT0OCP1 */
#define IOC_GPT0OCP2 0x400D4138 /**< GPT0OCP2 */
#define IOC_GPT1OCP1 0x400D413C /**< GPT1OCP1 */
#define IOC_GPT1OCP2 0x400D4140 /**< GPT1OCP2 */
#define IOC_GPT2OCP1 0x400D4144 /**< GPT2OCP1 */
#define IOC_GPT2OCP2 0x400D4148 /**< GPT2OCP2 */
#define IOC_GPT3OCP1 0x400D414C /**< GPT3OCP1 */
#define IOC_GPT3OCP2 0x400D4150 /**< GPT3OCP2 */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name I/O Control Register Bit Masks
* @{
*/
#define IOC_OVR_MASK 0x0000000F /**< IOC_Pxn_OVER registers */
#define IOC_PXX_SEL_MASK 0x0000001F /**< IOC_Pxn_SEL registers */
#define IOC_INPUT_SEL_MASK 0x0000001F /**< All other IOC registers */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name INPUT_SEL Values (For Pin Selection Registers)
* @{
*/
#define IOC_INPUT_SEL_PA0 0x00000000
#define IOC_INPUT_SEL_PA1 0x00000001
#define IOC_INPUT_SEL_PA2 0x00000002
#define IOC_INPUT_SEL_PA3 0x00000003
#define IOC_INPUT_SEL_PA4 0x00000004
#define IOC_INPUT_SEL_PA5 0x00000005
#define IOC_INPUT_SEL_PA6 0x00000006
#define IOC_INPUT_SEL_PA7 0x00000007
#define IOC_INPUT_SEL_PB0 0x00000008
#define IOC_INPUT_SEL_PB1 0x00000009
#define IOC_INPUT_SEL_PB2 0x0000000A
#define IOC_INPUT_SEL_PB3 0x0000000B
#define IOC_INPUT_SEL_PB4 0x0000000C
#define IOC_INPUT_SEL_PB5 0x0000000D
#define IOC_INPUT_SEL_PB6 0x0000000E
#define IOC_INPUT_SEL_PB7 0x0000000F
#define IOC_INPUT_SEL_PC0 0x00000010
#define IOC_INPUT_SEL_PC1 0x00000011
#define IOC_INPUT_SEL_PC2 0x00000012
#define IOC_INPUT_SEL_PC3 0x00000013
#define IOC_INPUT_SEL_PC4 0x00000014
#define IOC_INPUT_SEL_PC5 0x00000015
#define IOC_INPUT_SEL_PC6 0x00000016
#define IOC_INPUT_SEL_PC7 0x00000017
#define IOC_INPUT_SEL_PD0 0x00000018
#define IOC_INPUT_SEL_PD1 0x00000019
#define IOC_INPUT_SEL_PD2 0x0000001A
#define IOC_INPUT_SEL_PD3 0x0000001B
#define IOC_INPUT_SEL_PD4 0x0000001C
#define IOC_INPUT_SEL_PD5 0x0000001D
#define IOC_INPUT_SEL_PD6 0x0000001E
#define IOC_INPUT_SEL_PD7 0x0000001F
/** @} */
/*---------------------------------------------------------------------------*/
/** \name Peripheral Signal Select Values (for IOC_Pxx_SEL registers)
* @{
*/
#define IOC_PXX_SEL_UART0_TXD 0x00000000
#define IOC_PXX_SEL_UART1_RTS 0x00000001
#define IOC_PXX_SEL_UART1_TXD 0x00000002
#define IOC_PXX_SEL_SSI0_TXD 0x00000003
#define IOC_PXX_SEL_SSI0_CLKOUT 0x00000004
#define IOC_PXX_SEL_SSI0_FSSOUT 0x00000005
#define IOC_PXX_SEL_SSI0_STXSER_EN 0x00000006
#define IOC_PXX_SEL_SSI1_TXD 0x00000007
#define IOC_PXX_SEL_SSI1_CLKOUT 0x00000008
#define IOC_PXX_SEL_SSI1_FSSOUT 0x00000009
#define IOC_PXX_SEL_SSI1_STXSER_EN 0x0000000A
#define IOC_PXX_SEL_I2C_CMSSDA 0x0000000B
#define IOC_PXX_SEL_I2C_CMSSCL 0x0000000C
#define IOC_PXX_SEL_GPT0_ICP1 0x0000000D
#define IOC_PXX_SEL_GPT0_ICP2 0x0000000E
#define IOC_PXX_SEL_GPT1_ICP1 0x0000000F
#define IOC_PXX_SEL_GPT1_ICP2 0x00000010
#define IOC_PXX_SEL_GPT2_ICP1 0x00000011
#define IOC_PXX_SEL_GPT2_ICP2 0x00000012
#define IOC_PXX_SEL_GPT3_ICP1 0x00000013
#define IOC_PXX_SEL_GPT3_ICP2 0x00000014
/** @} */
/*---------------------------------------------------------------------------*/
/** \name Values for IOC_PXX_OVER
* @{
*/
#define IOC_OVERRIDE_OE 0x00000008 /**< Output Enable */
#define IOC_OVERRIDE_PUE 0x00000004 /**< Pull Up Enable */
#define IOC_OVERRIDE_PDE 0x00000002 /**< Pull Down Enable */
#define IOC_OVERRIDE_ANA 0x00000001 /**< Analog Enable */
#define IOC_OVERRIDE_DIS 0x00000000 /**< Override Disabled */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name IOC Functions
* @{
*/
/** \brief Initialise the IOC driver */
void ioc_init();
/**
* \brief Set Port:Pin override function
* \param port The port as a number (PA: 0, PB: 1 etc)
* \param pin The pin as a number
* \param over The desired override configuration
*
* \e over can take the following values:
*
* - IOC_OVERRIDE_OE: Output
* - IOC_OVERRIDE_PUE: Pull-Up
* - IOC_OVERRIDE_PDE: Pull-Down
* - IOC_OVERRIDE_ANA: Analog
* - IOC_OVERRIDE_DIS: Disabled
*/
void ioc_set_over(uint8_t port, uint8_t pin, uint8_t over);
/**
* \brief Function select for Port:Pin
* \param port The port as a number (PA: 0, PB: 1 etc)
* \param pin The pin as a number
* \param sel The desired function
*
* The value of \e sel can be any of the IOC_PXX_SEL_xyz defines. For example
* IOC_PXX_SEL_UART0_TXD will set the port to act as UART0 TX
*/
void ioc_set_sel(uint8_t port, uint8_t pin, uint8_t sel);
/**
* \brief Generates an IOC_INPUT_SEL_PXn value from a port/pin number
* \param port The port as a number (PA: 0, PB: 1 etc)
* \param pin The pin as a number
* \return A value which can be written in the INPUT_SEL bits of various IOC
* registers
*/
#define ioc_input_sel(port, pin) ((port << 3) | pin)
/** @} */
#endif /* IOC_H_ */
/**
* @}
* @}
*/

68
cpu/cc2538/dev/mpu.h Normal file
View File

@ -0,0 +1,68 @@
/*
* 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 cc2538
* @{
*
* \defgroup cc2538-mpu cc2538 Memory Protection Unit
*
* Driver for the cc2538 Memory Protection Unit
* @{
*
* \file
* Header file for the ARM Memory Protection Unit
*/
#ifndef MPU_H_
#define MPU_H_
#define MPU_MPU_TYPE 0xE000ED90 /**< MPU Type */
#define MPU_MPU_CTRL 0xE000ED94 /**< MPU Control */
#define MPU_MPU_NUMBER 0xE000ED98 /**< MPU Region Number */
#define MPU_MPU_BASE 0xE000ED9C /**< MPU Region Base Address */
#define MPU_MPU_ATTR 0xE000EDA0 /**< MPU Region Attribute and Size */
#define MPU_MPU_BASE1 0xE000EDA4 /**< MPU Region Base Address Alias 1 */
#define MPU_MPU_ATTR1 0xE000EDA8 /**< MPU Region Attribute and Size Alias 1 */
#define MPU_MPU_BASE2 0xE000EDAC /**< MPU Region Base Address Alias 2 */
#define MPU_MPU_ATTR2 0xE000EDB0 /**< MPU Region Attribute and Size Alias 2*/
#define MPU_MPU_BASE3 0xE000EDB4 /**< MPU Region Base Address Alias 3 */
#define MPU_MPU_ATTR3 0xE000EDB8 /**< MPU Region Attribute and Size Alias 3*/
#define MPU_DBG_CTRL 0xE000EDF0 /**< Debug Control and Status Reg */
#define MPU_DBG_XFER 0xE000EDF4 /**< Debug Core Reg. Transfer Select */
#define MPU_DBG_DATA 0xE000EDF8 /**< Debug Core Register Data */
#define MPU_DBG_INT 0xE000EDFC /**< Debug Reset Interrupt Control */
#define MPU_SW_TRIG 0xE000EF00 /**< Software Trigger Interrupt */
#endif /* MPU_H_ */
/**
* @}
* @}
*/

111
cpu/cc2538/dev/nvic.c Normal file
View File

@ -0,0 +1,111 @@
/*
* 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 cc2538-nvic
* @{
*
* \file
* Driver for the cc2538 NVIC
* All interrupt-related functionality is implemented here
*/
#include "contiki.h"
#include "dev/nvic.h"
#include "dev/scb.h"
#include "reg.h"
#include <stdint.h>
static uint32_t *interrupt_enable;
static uint32_t *interrupt_disable;
static uint32_t *interrupt_pend;
static uint32_t *interrupt_unpend;
/*---------------------------------------------------------------------------*/
void
nvic_init()
{
interrupt_enable = (uint32_t *)NVIC_EN0;
interrupt_disable = (uint32_t *)NVIC_DIS0;
interrupt_pend = (uint32_t *)NVIC_PEND0;
interrupt_unpend = (uint32_t *)NVIC_UNPEND0;
/* Provide our interrupt table to the NVIC */
REG(SCB_VTABLE) = (NVIC_CONF_VTABLE_BASE | NVIC_CONF_VTABLE_OFFSET);
}
/*---------------------------------------------------------------------------*/
void
nvic_interrupt_enable(uint32_t intr)
{
/* Writes of 0 are ignored, which is why we can simply use = */
interrupt_enable[intr >> 5] = 1 << (intr & 0x1F);
}
/*---------------------------------------------------------------------------*/
void
nvic_interrupt_disable(uint32_t intr)
{
/* Writes of 0 are ignored, which is why we can simply use = */
interrupt_disable[intr >> 5] = 1 << (intr & 0x1F);
}
/*---------------------------------------------------------------------------*/
void
nvic_interrupt_en_restore(uint32_t intr, uint8_t v)
{
if(v != 1) {
return;
}
interrupt_enable[intr >> 5] = 1 << (intr & 0x1F);
}
/*---------------------------------------------------------------------------*/
uint8_t
nvic_interrupt_en_save(uint32_t intr)
{
uint8_t rv = ((interrupt_enable[intr >> 5] & (1 << (intr & 0x1F)))
> NVIC_INTERRUPT_DISABLED);
nvic_interrupt_disable(intr);
return rv;
}
/*---------------------------------------------------------------------------*/
void
nvic_interrupt_pend(uint32_t intr)
{
/* Writes of 0 are ignored, which is why we can simply use = */
interrupt_pend[intr >> 5] = 1 << (intr & 0x1F);
}
/*---------------------------------------------------------------------------*/
void
nvic_interrupt_unpend(uint32_t intr)
{
/* Writes of 0 are ignored, which is why we can simply use = */
interrupt_unpend[intr >> 5] = 1 << (intr & 0x1F);
}
/** @} */

248
cpu/cc2538/dev/nvic.h Normal file
View File

@ -0,0 +1,248 @@
/*
* 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 cc2538
* @{
*
* \defgroup cc2538-nvic cc2538 Nested Vectored Interrupt Controller
*
* Driver for the cc2538 NVIC controller
* @{
*
* \file
* Header file for the ARM Nested Vectored Interrupt Controller
*/
#ifndef NVIC_H_
#define NVIC_H_
#include <stdint.h>
/*---------------------------------------------------------------------------*/
/** \name NVIC Constants and Configuration
* @{
*/
#define NVIC_VTABLE_IN_SRAM 0x20000000
#define NVIC_VTABLE_IN_CODE 0x00000000
#define NVIC_INTERRUPT_ENABLED 0x00000001
#define NVIC_INTERRUPT_DISABLED 0x00000000
#ifndef NVIC_CONF_VTABLE_BASE
#define NVIC_CONF_VTABLE_BASE NVIC_VTABLE_IN_CODE
#endif
#ifndef NVIC_CONF_VTABLE_OFFSET
#define NVIC_CONF_VTABLE_OFFSET 0x200000
#endif
/** @} */
/*---------------------------------------------------------------------------*/
/** \name NVIC Interrupt assignments
* @{
*/
#define NVIC_INT_GPIO_PORT_A 0 /**< GPIO port A */
#define NVIC_INT_GPIO_PORT_B 1 /**< GPIO port B */
#define NVIC_INT_GPIO_PORT_C 2 /**< GPIO port C */
#define NVIC_INT_GPIO_PORT_D 3 /**< GPIO port D */
#define NVIC_INT_UART0 5 /**< UART0 */
#define NVIC_INT_UART1 6 /**< UART1 */
#define NVIC_INT_SSI0 7 /**< SSI0 */
#define NVIC_INT_I2C 8 /**< I2C */
#define NVIC_INT_ADC 14 /**< ADC */
#define NVIC_INT_WDT 18 /**< Watchdog Timer */
#define NVIC_INT_GPTIMER_0A 19 /**< GPTimer 0A */
#define NVIC_INT_GPTIMER_0B 20 /**< GPTimer 0B */
#define NVIC_INT_GPTIMER_1A 21 /**< GPTimer 1A */
#define NVIC_INT_GPTIMER_1B 22 /**< GPTimer 1B */
#define NVIC_INT_GPTIMER_2A 23 /**< GPTimer 2A */
#define NVIC_INT_GPTIMER_2B 24 /**< GPTimer 2B */
#define NVIC_INT_ADC_CMP 25 /**< Analog Comparator */
#define NVIC_INT_RF_RXTX_ALT 26 /**< RF TX/RX (Alternate) */
#define NVIC_INT_RF_ERR_ALT 27 /**< RF Error (Alternate) */
#define NVIC_INT_SYS_CTRL 28 /**< System Control */
#define NVIC_INT_FLASH_CTRL 29 /**< Flash memory control */
#define NVIC_INT_AES_ALT 30 /**< AES (Alternate) */
#define NVIC_INT_PKA_ALT 31 /**< PKA (Alternate) */
#define NVIC_INT_SM_TIMER_ALT 32 /**< SM Timer (Alternate) */
#define NVIC_INT_MAC_TIMER_ALT 33 /**< MAC Timer (Alternate) */
#define NVIC_INT_SSI1 34 /**< SSI1 */
#define NVIC_INT_GPTIMER_3A 35 /**< GPTimer 3A */
#define NVIC_INT_GPTIMER_3B 36 /**< GPTimer 3B */
#define NVIC_INT_UDMA 46 /**< uDMA software */
#define NVIC_INT_UDMA_ERR 47 /**< uDMA error */
#define NVIC_INT_USB 140 /**< USB */
#define NVIC_INT_RF_RXTX 141 /**< RF Core Rx/Tx */
#define NVIC_INT_RF_ERR 142 /**< RF Core Error */
#define NVIC_INT_AES 143 /**< AES */
#define NVIC_INT_PKA 144 /**< PKA */
#define NVIC_INT_SM_TIMER 145 /**< SM Timer */
#define NVIC_INT_MACTIMER 146 /**< MAC Timer */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name NVIC Register Declarations
* @{
*/
#define NVIC_EN0 0xE000E100 /**< Interrupt 0-31 Set Enable */
#define NVIC_EN1 0xE000E104 /**< Interrupt 32-54 Set Enable */
#define NVIC_EN2 0xE000E108 /**< Interrupt 64-95 Set Enable */
#define NVIC_EN3 0xE000E10C /**< Interrupt 96-127 Set Enable */
#define NVIC_EN4 0xE000E110 /**< Interrupt 128-131 Set Enable */
#define NVIC_DIS0 0xE000E180 /**< Interrupt 0-31 Clear Enable */
#define NVIC_DIS1 0xE000E184 /**< Interrupt 32-54 Clear Enable */
#define NVIC_DIS2 0xE000E188 /**< Interrupt 64-95 Clear Enable */
#define NVIC_DIS3 0xE000E18C /**< Interrupt 96-127 Clear Enable */
#define NVIC_DIS4 0xE000E190 /**< Interrupt 128-131 Clear Enable */
#define NVIC_PEND0 0xE000E200 /**< Interrupt 0-31 Set Pending */
#define NVIC_PEND1 0xE000E204 /**< Interrupt 32-54 Set Pending */
#define NVIC_PEND2 0xE000E208 /**< Interrupt 64-95 Set Pending */
#define NVIC_PEND3 0xE000E20C /**< Interrupt 96-127 Set Pending */
#define NVIC_PEND4 0xE000E210 /**< Interrupt 128-131 Set Pending */
#define NVIC_UNPEND0 0xE000E280 /**< Interrupt 0-31 Clear Pending */
#define NVIC_UNPEND1 0xE000E284 /**< Interrupt 32-54 Clear Pending */
#define NVIC_UNPEND2 0xE000E288 /**< Interrupt 64-95 Clear Pending */
#define NVIC_UNPEND3 0xE000E28C /**< Interrupt 96-127 Clear Pending */
#define NVIC_UNPEND4 0xE000E290 /**< Interrupt 128-131 Clear Pending */
#define NVIC_ACTIVE0 0xE000E300 /**< Interrupt 0-31 Active Bit */
#define NVIC_ACTIVE1 0xE000E304 /**< Interrupt 32-54 Active Bit */
#define NVIC_ACTIVE2 0xE000E308 /**< Interrupt 64-95 Active Bit */
#define NVIC_ACTIVE3 0xE000E30C /**< Interrupt 96-127 Active Bit */
#define NVIC_ACTIVE4 0xE000E310 /**< Interrupt 128-131 Active Bit */
#define NVIC_PRI0 0xE000E400 /**< Interrupt 0-3 Priority */
#define NVIC_PRI1 0xE000E404 /**< Interrupt 4-7 Priority */
#define NVIC_PRI2 0xE000E408 /**< Interrupt 8-11 Priority */
#define NVIC_PRI3 0xE000E40C /**< Interrupt 12-15 Priority */
#define NVIC_PRI4 0xE000E410 /**< Interrupt 16-19 Priority */
#define NVIC_PRI5 0xE000E414 /**< Interrupt 20-23 Priority */
#define NVIC_PRI6 0xE000E418 /**< Interrupt 24-27 Priority */
#define NVIC_PRI7 0xE000E41C /**< Interrupt 28-31 Priority */
#define NVIC_PRI8 0xE000E420 /**< Interrupt 32-35 Priority */
#define NVIC_PRI9 0xE000E424 /**< Interrupt 36-39 Priority */
#define NVIC_PRI10 0xE000E428 /**< Interrupt 40-43 Priority */
#define NVIC_PRI11 0xE000E42C /**< Interrupt 44-47 Priority */
#define NVIC_PRI12 0xE000E430 /**< Interrupt 48-51 Priority */
#define NVIC_PRI13 0xE000E434 /**< Interrupt 52-53 Priority */
#define NVIC_PRI14 0xE000E438 /**< Interrupt 56-59 Priority */
#define NVIC_PRI15 0xE000E43C /**< Interrupt 60-63 Priority */
#define NVIC_PRI16 0xE000E440 /**< Interrupt 64-67 Priority */
#define NVIC_PRI17 0xE000E444 /**< Interrupt 68-71 Priority */
#define NVIC_PRI18 0xE000E448 /**< Interrupt 72-75 Priority */
#define NVIC_PRI19 0xE000E44C /**< Interrupt 76-79 Priority */
#define NVIC_PRI20 0xE000E450 /**< Interrupt 80-83 Priority */
#define NVIC_PRI21 0xE000E454 /**< Interrupt 84-87 Priority */
#define NVIC_PRI22 0xE000E458 /**< Interrupt 88-91 Priority */
#define NVIC_PRI23 0xE000E45C /**< Interrupt 92-95 Priority */
#define NVIC_PRI24 0xE000E460 /**< Interrupt 96-99 Priority */
#define NVIC_PRI25 0xE000E464 /**< Interrupt 100-103 Priority */
#define NVIC_PRI26 0xE000E468 /**< Interrupt 104-107 Priority */
#define NVIC_PRI27 0xE000E46C /**< Interrupt 108-111 Priority */
#define NVIC_PRI28 0xE000E470 /**< Interrupt 112-115 Priority */
#define NVIC_PRI29 0xE000E474 /**< Interrupt 116-119 Priority */
#define NVIC_PRI30 0xE000E478 /**< Interrupt 120-123 Priority */
#define NVIC_PRI31 0xE000E47C /**< Interrupt 124-127 Priority */
#define NVIC_PRI32 0xE000E480 /**< Interrupt 128-131 Priority */
#define NVIC_PRI33 0xE000E480 /**< Interrupt 132-135 Priority */
#define NVIC_PRI34 0xE000E484 /**< Interrupt 136-139 Priority */
#define NVIC_PRI35 0xE000E488 /**< Interrupt 140-143 Priority */
#define NVIC_PRI36 0xE000E48c /**< Interrupt 144-147 Priority */
/** @} */
/*---------------------------------------------------------------------------*/
/** \brief Initialises the NVIC driver */
void nvic_init();
/**
* \brief Enables interrupt intr
* \param intr The interrupt number (NOT the vector number). For example,
* GPIO Port A interrupt is 0, not 16.
*
* Possible values for the \e intr param are defined as NVIC_INT_xyz. For
* instance, to enable the GPIO Port A interrupt, pass NVIC_INT_GPIO_PORT_A
*/
void nvic_interrupt_enable(uint32_t intr);
/**
* \brief Disables interrupt intr
* \param intr The interrupt number (NOT the vector number). For example,
* GPIO Port A interrupt is 0, not 16.
*
* Possible values for the \e intr param are defined as NVIC_INT_xyz. For
* instance, to disable the GPIO Port A interrupt, pass NVIC_INT_GPIO_PORT_A
*/
void nvic_interrupt_disable(uint32_t intr);
/**
* \brief Enables interrupt intr if v > 0
* \param intr The interrupt number (NOT the vector number). For example,
* GPIO Port A interrupt is 0, not 16.
* \param v 0: No effect, 1: Enables the interrupt
*
* This function is useful to restore an interrupt to a state previously
* saved by nvic_interrupt_en_save. Thus, if when nvic_interrupt_en_save was
* called the interrupt was enabled, this function will re-enabled it.
* Possible values for the \e intr param are defined as NVIC_INT_xyz. For
* instance, to disable the GPIO Port A interrupt, pass NVIC_INT_GPIO_PORT_A
*/
void nvic_interrupt_en_restore(uint32_t intr, uint8_t v);
/**
* \brief Checks the interrupt enabled status for intr
* \param intr The interrupt number (NOT the vector number). For example,
* GPIO Port A interrupt is 0, not 16.
* \return 1: Enabled, 0: Disabled
*
* Possible values for the \e intr param are defined as NVIC_INT_xyz. For
* instance, to disable the GPIO Port A interrupt, pass NVIC_INT_GPIO_PORT_A
*/
uint8_t nvic_interrupt_en_save(uint32_t intr);
/**
* \brief Sets intr to pending
* \param intr The interrupt number (NOT the vector number). For example,
* GPIO Port A interrupt is 0, not 16.
*
* Possible values for the \e intr param are defined as NVIC_INT_xyz. For
* instance, to enable the GPIO Port A interrupt, pass NVIC_INT_GPIO_PORT_A
*/
void nvic_interrupt_pend(uint32_t intr);
/**
* \brief Sets intr to no longer pending
* \param intr The interrupt number (NOT the vector number). For example,
* GPIO Port A interrupt is 0, not 16.
*
* Possible values for the \e intr param are defined as NVIC_INT_xyz. For
* instance, to disable the GPIO Port A interrupt, pass NVIC_INT_GPIO_PORT_A
*/
void nvic_interrupt_unpend(uint32_t intr);
#endif /* NVIC_H_ */
/**
* @}
* @}
*/

133
cpu/cc2538/dev/random.c Normal file
View File

@ -0,0 +1,133 @@
/*
* 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 cc2538
* @{
*
* \defgroup cc2538-random cc2538 Random Number Generator
*
* Driver for the cc2538 Hardware Random Number Generator
* @{
*
* \file
* Random number generator routines exploiting the cc2538 hardware
* capabilities.
*
* This file overrides core/lib/random.c.
*/
#include "contiki.h"
#include "dev/rfcore.h"
#include "dev/cc2538-rf.h"
#include "dev/soc-adc.h"
#include "dev/sys-ctrl.h"
#include "reg.h"
/*---------------------------------------------------------------------------*/
/**
* \brief Generates a new random number using the cc2538 RNG.
* \return The random number.
*/
unsigned short
random_rand(void)
{
uint32_t rv;
/* Clock the RNG LSFR once */
REG(SOC_ADC_ADCCON1) |= SOC_ADC_ADCCON1_RCTRL0;
rv = REG(SOC_ADC_RNDL) | (REG(SOC_ADC_RNDH) << 8);
return ((unsigned short)rv);
}
/*---------------------------------------------------------------------------*/
/**
* \brief Seed the cc2538 random number generator.
* \param seed Ignored. It's here because the function prototype is in core.
*
* We form a seed for the RNG by sampling IF_ADC as
* discussed in the user guide.
* Seeding with this method should not be done during
* normal radio operation. Thus, use this function before
* initialising the network.
*
* \note Must not be called after the RF driver has been initialised and is
* in normal operation. If it is absolutely necessary to do so, the
* radio will need re-initialised.
*/
void
random_init(unsigned short seed)
{
int i;
unsigned short s = 0;
/* Make sure the RNG is on */
REG(SOC_ADC_ADCCON1) &= ~(SOC_ADC_ADCCON1_RCTRL1 | SOC_ADC_ADCCON1_RCTRL0);
/* Enable clock for the RF Core */
REG(SYS_CTRL_RCGCRFC) = 1;
/* Infinite RX - FRMCTRL0[3:2] = 10
* This will mess with radio operation - see note above */
REG(RFCORE_XREG_FRMCTRL0) = 0x00000008;
/* Turn RF on */
CC2538_RF_CSP_ISRXON();
/*
* Wait until "the chip has been in RX long enough for the transients to
* have died out. A convenient way to do this is to wait for the RSSI-valid
* signal to go high."
*/
while(!(REG(RFCORE_XREG_RSSISTAT) & RFCORE_XREG_RSSISTAT_RSSI_VALID));
/*
* Form the seed by concatenating bits from IF_ADC in the RF receive path.
* Keep sampling until we have read at least 16 bits AND the seed is valid
*
* Invalid seeds are 0x0000 and 0x8003 and should not be used.
*/
while(s == 0x0000 || s == 0x8003) {
for(i = 0; i < 16; i++) {
s |= (REG(RFCORE_XREG_RFRND) & RFCORE_XREG_RFRND_IRND);
s <<= 1;
}
}
/* High byte first */
REG(SOC_ADC_RNDL) = (s >> 8) & 0x00FF;
REG(SOC_ADC_RNDL) = s & 0xFF;
/* RF Off. NETSTACK_RADIO.init() will sort out normal RF operation */
CC2538_RF_CSP_ISRFOFF();
}
/**
* @}
* @}
*/

View File

@ -0,0 +1,126 @@
/*
* 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 cc2538-rfcore
* @{
*
* \file
* Header with declarations of the RF Core FFSM registers.
*/
#ifndef RFCORE_FFSM_H_
#define RFCORE_FFSM_H_
/*---------------------------------------------------------------------------*/
/** \name RFCORE_FFSM register offsets
* @{
*/
#define RFCORE_FFSM_SRCRESMASK0 0x40088580 /**< Src addr matching result */
#define RFCORE_FFSM_SRCRESMASK1 0x40088584 /**< Src addr matching result */
#define RFCORE_FFSM_SRCRESMASK2 0x40088588 /**< Src addr matching result */
#define RFCORE_FFSM_SRCRESINDEX 0x4008858C /**< Src addr matching result */
#define RFCORE_FFSM_SRCEXTPENDEN0 0x40088590 /**< Src addr matching control */
#define RFCORE_FFSM_SRCEXTPENDEN1 0x40088594 /**< Src addr matching control */
#define RFCORE_FFSM_SRCEXTPENDEN2 0x40088598 /**< Src addr matching control */
#define RFCORE_FFSM_SRCSHORTPENDEN0 0x4008859C /**< Src addr matching control */
#define RFCORE_FFSM_SRCSHORTPENDEN1 0x400885A0 /**< Src addr matching control */
#define RFCORE_FFSM_SRCSHORTPENDEN2 0x400885A4 /**< Src addr matching control */
#define RFCORE_FFSM_EXT_ADDR0 0x400885A8 /**< Local address information */
#define RFCORE_FFSM_EXT_ADDR1 0x400885AC /**< Local address information */
#define RFCORE_FFSM_EXT_ADDR2 0x400885B0 /**< Local address information */
#define RFCORE_FFSM_EXT_ADDR3 0x400885B4 /**< Local address information */
#define RFCORE_FFSM_EXT_ADDR4 0x400885B8 /**< Local address information */
#define RFCORE_FFSM_EXT_ADDR5 0x400885BC /**< Local address information */
#define RFCORE_FFSM_EXT_ADDR6 0x400885C0 /**< Local address information */
#define RFCORE_FFSM_EXT_ADDR7 0x400885C4 /**< Local address information */
#define RFCORE_FFSM_PAN_ID0 0x400885C8 /**< Local address information */
#define RFCORE_FFSM_PAN_ID1 0x400885CC /**< Local address information */
#define RFCORE_FFSM_SHORT_ADDR0 0x400885D0 /**< Local address information */
#define RFCORE_FFSM_SHORT_ADDR1 0x400885D4 /**< Local address information */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_FFSM_SRCRESMASK[0:2] register bit masks
* @{
*/
#define RFCORE_FFSM_SRCRESMASK0_SRCRESMASK0 0x000000FF /**< Ext addr match */
#define RFCORE_FFSM_SRCRESMASK1_SRCRESMASK1 0x000000FF /**< Short addr match */
#define RFCORE_FFSM_SRCRESMASK2_SRCRESMASK2 0x000000FF /**< 24-bit mask */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_FFSM_SRCRESINDEX register bit masks
* @{
*/
#define RFCORE_FFSM_SRCRESINDEX_SRCRESINDEX 0x000000FF /**< LS Entry bit index */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_FFSM_SRCEXTPENDEN[0:2] register bit masks
* @{
*/
#define RFCORE_FFSM_SRCEXTPENDEN0_SRCEXTPENDEN0 0x000000FF /**< 8 LSBs */
#define RFCORE_FFSM_SRCEXTPENDEN1_SRCEXTPENDEN1 0x000000FF /**< 8 middle bits */
#define RFCORE_FFSM_SRCEXTPENDEN2_SRCEXTPENDEN2 0x000000FF /**< 8 MSBs */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_FFSM_SRCSHORTPENDEN[0:2] register bit masks
* @{
*/
#define RFCORE_FFSM_SRCSHORTPENDEN0_SRCSHORTPENDEN0 0x000000FF /**< 8 LSBs */
#define RFCORE_FFSM_SRCSHORTPENDEN1_SRCSHORTPENDEN1 0x000000FF /**< 8 middle */
#define RFCORE_FFSM_SRCSHORTPENDEN2_SRCSHORTPENDEN2 0x000000FF /**< 8 MSBs */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_FFSM_EXT_ADDR[0:7] register bit masks
* @{
*/
#define RFCORE_FFSM_EXT_ADDR0_EXT_ADDR0 0x000000FF /**< EXT_ADDR[7:0] */
#define RFCORE_FFSM_EXT_ADDR1_EXT_ADDR1 0x000000FF /**< EXT_ADDR[15:8] */
#define RFCORE_FFSM_EXT_ADDR2_EXT_ADDR2 0x000000FF /**< EXT_ADDR[23:16] */
#define RFCORE_FFSM_EXT_ADDR3_EXT_ADDR3 0x000000FF /**< EXT_ADDR[31:24] */
#define RFCORE_FFSM_EXT_ADDR4_EXT_ADDR4 0x000000FF /**< EXT_ADDR[39:32] */
#define RFCORE_FFSM_EXT_ADDR5_EXT_ADDR5 0x000000FF /**< EXT_ADDR[47:40] */
#define RFCORE_FFSM_EXT_ADDR6_EXT_ADDR6 0x000000FF /**< EXT_ADDR[55:48] */
#define RFCORE_FFSM_EXT_ADDR7_EXT_ADDR7 0x000000FF /**< EXT_ADDR[63:56] */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_FFSM_PAN_ID[0:1] register bit masks
* @{
*/
#define RFCORE_FFSM_PAN_ID0_PAN_ID0 0x000000FF /**< PAN_ID[7:0] */
#define RFCORE_FFSM_PAN_ID1_PAN_ID1 0x000000FF /**< PAN_ID[15:8] */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_FFSM_SHORT_ADDR[0:1] register bit masks
* @{
*/
#define RFCORE_FFSM_SHORT_ADDR0_SHORT_ADDR0 0x000000FF /**< SHORT_ADDR[7:0] */
#define RFCORE_FFSM_SHORT_ADDR1_SHORT_ADDR1 0x000000FF /**< SHORT_ADDR[15:8] */
/** @} */
#endif /* RFCORE_FFSM_H_ */
/** @} */

176
cpu/cc2538/dev/rfcore-sfr.h Normal file
View File

@ -0,0 +1,176 @@
/*
* 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 cc2538-rfcore
* @{
*
* \file
* Header with declarations of the RF Core SFR registers. Includes
* declarations of MAC timer registers.
*/
#ifndef RFCORE_SFR_H_
#define RFCORE_SFR_H_
/*---------------------------------------------------------------------------*/
/** \name RFCORE_SFR register offsets (MAC Timer)
* @{
*/
#define RFCORE_SFR_MTCSPCFG 0x40088800 /**< MAC Timer event configuration */
#define RFCORE_SFR_MTCTRL 0x40088804 /**< MAC Timer control register */
#define RFCORE_SFR_MTIRQM 0x40088808 /**< MAC Timer interrupt mask */
#define RFCORE_SFR_MTIRQF 0x4008880C /**< MAC Timer interrupt flags */
#define RFCORE_SFR_MTMSEL 0x40088810 /**< MAC Timer multiplex select */
#define RFCORE_SFR_MTM0 0x40088814 /**< MAC Timer MUX register 0 */
#define RFCORE_SFR_MTM1 0x40088818 /**< MAC Timer MUX register 1 */
#define RFCORE_SFR_MTMOVF2 0x4008881C /**< MAC Timer MUX overflow 2 */
#define RFCORE_SFR_MTMOVF1 0x40088820 /**< MAC Timer MUX overflow 1 */
#define RFCORE_SFR_MTMOVF0 0x40088824 /**< MAC Timer MUX overflow 0 */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_SFR register offsets (RF)
* @{
*/
#define RFCORE_SFR_RFDATA 0x40088828 /**< TX/RX FIFO data */
#define RFCORE_SFR_RFERRF 0x4008882C /**< RF error interrupt flags */
#define RFCORE_SFR_RFIRQF1 0x40088830 /**< RF interrupt flags */
#define RFCORE_SFR_RFIRQF0 0x40088834 /**< RF interrupt flags */
#define RFCORE_SFR_RFST 0x40088838 /**< RF CSMA-CA/strobe processor */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_SFR_MTCSPCFG register bit masks
* @{
*/
#define RFCORE_SFR_MTCSPCFG_MACTIMER_EVENMT_CFG 0x00000070 /**< MT_EVENT2 pulse event trigger */
#define RFCORE_SFR_MTCSPCFG_MACTIMER_EVENT1_CFG 0x00000007 /**< MT_EVENT1 pulse event trigger */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_SFR_MTCTRL register bit masks
* @{
*/
#define RFCORE_SFR_MTCTRL_LATCH_MODE 0x00000008 /**< OVF counter latch mode */
#define RFCORE_SFR_MTCTRL_STATE 0x00000004 /**< State of MAC Timer */
#define RFCORE_SFR_MTCTRL_SYNC 0x00000002 /**< Timer start/stop timing */
#define RFCORE_SFR_MTCTRL_RUN 0x00000001 /**< Timer start/stop */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_SFR_MTIRQM register bit masks
* @{
*/
#define RFCORE_SFR_MTIRQM_MACTIMER_OVF_COMPARE2M 0x00000020 /**< MACTIMER_OVF_COMPARE2 mask */
#define RFCORE_SFR_MTIRQM_MACTIMER_OVF_COMPARE1M 0x00000010 /**< MACTIMER_OVF_COMPARE1 mask */
#define RFCORE_SFR_MTIRQM_MACTIMER_OVF_PERM 0x00000008 /**< MACTIMER_OVF_PER mask */
#define RFCORE_SFR_MTIRQM_MACTIMER_COMPARE2M 0x00000004 /**< MACTIMER_COMPARE2 mask */
#define RFCORE_SFR_MTIRQM_MACTIMER_COMPARE1M 0x00000002 /**< MACTIMER_COMPARE1 mask */
#define RFCORE_SFR_MTIRQM_MACTIMER_PERM 0x00000001 /**< MACTIMER_PER mask */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_SFR_MTIRQF register bit masks
* @{
*/
#define RFCORE_SFR_MTIRQF_MACTIMER_OVF_COMPARE2F 0x00000020 /**< MACTIMER_OVF_COMPARE2 flag */
#define RFCORE_SFR_MTIRQF_MACTIMER_OVF_COMPARE1F 0x00000010 /**< MACTIMER_OVF_COMPARE1 flag */
#define RFCORE_SFR_MTIRQF_MACTIMER_OVF_PERF 0x00000008 /**< MACTIMER_OVF_PER flag */
#define RFCORE_SFR_MTIRQF_MACTIMER_COMPARE2F 0x00000004 /**< MACTIMER_COMPARE2 flag */
#define RFCORE_SFR_MTIRQF_MACTIMER_COMPARE1F 0x00000002 /**< MACTIMER_COMPARE1 flag */
#define RFCORE_SFR_MTIRQF_MACTIMER_PERF 0x00000001 /**< MACTIMER_PER flag */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_SFR_MTMSEL register bit masks
* @{
*/
#define RFCORE_SFR_MTMSEL_MTMOVFSEL 0x00000070 /**< MTMOVF register select */
#define RFCORE_SFR_MTMSEL_MTMSEL 0x00000007 /**< MTM register select */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_SFR_MTM[0:2] register bit masks
* @{
*/
#define RFCORE_SFR_MTM0_MTM0 0x000000FF /**< Register[7:0] */
#define RFCORE_SFR_MTM1_MTM1 0x000000FF /**< Register[15:8] */
#define RFCORE_SFR_MTMOVF2_MTMOVF2 0x000000FF /**< Register[23:16] */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_SFR_MTMOVF[1:0] register bit masks
* @{
*/
#define RFCORE_SFR_MTMOVF1_MTMOVF1 0x000000FF /**< Register[15:8] */
#define RFCORE_SFR_MTMOVF0_MTMOVF0 0x000000FF /**< Register[7:0] */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_SFR_RFDATA register bit masks
* @{
*/
#define RFCORE_SFR_RFDATA_RFD 0x000000FF /**< Read/Write Data from RF FIFO */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_SFR_RFERRF register bit masks
* @{
*/
#define RFCORE_SFR_RFERRF_STROBEERR 0x00000040 /**< Strobe error */
#define RFCORE_SFR_RFERRF_TXUNDERF 0x00000020 /**< TX FIFO underflowed */
#define RFCORE_SFR_RFERRF_TXOVERF 0x00000010 /**< TX FIFO overflowed */
#define RFCORE_SFR_RFERRF_RXUNDERF 0x00000008 /**< RX FIFO underflowed */
#define RFCORE_SFR_RFERRF_RXOVERF 0x00000004 /**< RX FIFO overflowed */
#define RFCORE_SFR_RFERRF_RXABO 0x00000002 /**< Frame RX was aborted */
#define RFCORE_SFR_RFERRF_NLOCK 0x00000001 /**< Frequency synthesizer lock error */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_SFR_RFIRQF1 register bit masks
* @{
*/
#define RFCORE_SFR_RFIRQF1_CSP_WAIT 0x00000020 /**< CSP Execution continued */
#define RFCORE_SFR_RFIRQF1_CSP_STOP 0x00000010 /**< CSP has stopped program */
#define RFCORE_SFR_RFIRQF1_CSP_MANINT 0x00000008 /**< CSP Manual interrupt */
#define RFCORE_SFR_RFIRQF1_RFIDLE 0x00000004 /**< IDLE state entered */
#define RFCORE_SFR_RFIRQF1_TXDONE 0x00000002 /**< Complete frame TX finished */
#define RFCORE_SFR_RFIRQF1_TXACKDONE 0x00000001 /**< ACK frame TX finished */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_SFR_RFIRQF0 register bit masks
* @{
*/
#define RFCORE_SFR_RFIRQF0_RXMASKZERO 0x00000080 /**< RXENABLE gone all-zero */
#define RFCORE_SFR_RFIRQF0_RXPKTDONE 0x00000040 /**< Complete frame RX */
#define RFCORE_SFR_RFIRQF0_FRAME_ACCEPTED 0x00000020 /**< Frame has passed frame filter */
#define RFCORE_SFR_RFIRQF0_SRC_MATCH_FOUND 0x00000010 /**< Source match is found */
#define RFCORE_SFR_RFIRQF0_SRC_MATCH_DONE 0x00000008 /**< Source matching is complete */
#define RFCORE_SFR_RFIRQF0_FIFOP 0x00000004 /**< RX FIFO exceeded threshold */
#define RFCORE_SFR_RFIRQF0_SFD 0x00000002 /**< SFD TX or RX */
#define RFCORE_SFR_RFIRQF0_ACT_UNUSED 0x00000001 /**< Reserved */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_SFR_RFST register bit masks
* @{
*/
#define RFCORE_SFR_RFST_INSTR 0x000000FF /**< Data written to this register */
/** @} */
#endif /* RFCORE_SFR_H_ */
/** @} */

View File

@ -0,0 +1,671 @@
/*
* 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 cc2538-rfcore
* @{
*
* \file
* Header with declarations of the RF Core XREGs.
*/
#ifndef RFCORE_XREG_H_
#define RFCORE_XREG_H_
/*---------------------------------------------------------------------------*/
/** \name RFCORE_FFSM register offsets
* @{
*/
#define RFCORE_XREG_FRMFILT0 0x40088600 /**< Frame filtering control */
#define RFCORE_XREG_FRMFILT1 0x40088604 /**< Frame filtering control */
#define RFCORE_XREG_SRCMATCH 0x40088608 /**< Source address matching */
#define RFCORE_XREG_SRCSHORTEN0 0x4008860C /**< Short address matching */
#define RFCORE_XREG_SRCSHORTEN1 0x40088610 /**< Short address matching */
#define RFCORE_XREG_SRCSHORTEN2 0x40088614 /**< Short address matching */
#define RFCORE_XREG_SRCEXTEN0 0x40088618 /**< Extended address matching */
#define RFCORE_XREG_SRCEXTEN1 0x4008861C /**< Extended address matching */
#define RFCORE_XREG_SRCEXTEN2 0x40088620 /**< Extended address matching */
#define RFCORE_XREG_FRMCTRL0 0x40088624 /**< Frame handling */
#define RFCORE_XREG_FRMCTRL1 0x40088628 /**< Frame handling */
#define RFCORE_XREG_RXENABLE 0x4008862C /**< RX enabling */
#define RFCORE_XREG_RXMASKSET 0x40088630 /**< RX enabling */
#define RFCORE_XREG_RXMASKCLR 0x40088634 /**< RX disabling */
#define RFCORE_XREG_FREQTUNE 0x40088638 /**< Crystal oscillator freq tuning */
#define RFCORE_XREG_FREQCTRL 0x4008863C /**< Controls the RF frequency */
#define RFCORE_XREG_TXPOWER 0x40088640 /**< Controls the output power */
#define RFCORE_XREG_TXCTRL 0x40088644 /**< Controls the TX settings */
#define RFCORE_XREG_FSMSTAT0 0x40088648 /**< Radio status register */
#define RFCORE_XREG_FSMSTAT1 0x4008864C /**< Radio status register */
#define RFCORE_XREG_FIFOPCTRL 0x40088650 /**< FIFOP threshold */
#define RFCORE_XREG_FSMCTRL 0x40088654 /**< FSM options */
#define RFCORE_XREG_CCACTRL0 0x40088658 /**< CCA threshold */
#define RFCORE_XREG_CCACTRL1 0x4008865C /**< Other CCA Options */
#define RFCORE_XREG_RSSI 0x40088660 /**< RSSI status register */
#define RFCORE_XREG_RSSISTAT 0x40088664 /**< RSSI valid status register */
#define RFCORE_XREG_RXFIRST 0x40088668 /**< First byte in RX FIFO */
#define RFCORE_XREG_RXFIFOCNT 0x4008866C /**< Number of bytes in RX FIFO */
#define RFCORE_XREG_TXFIFOCNT 0x40088670 /**< Number of bytes in TX FIFO */
#define RFCORE_XREG_RXFIRST_PTR 0x40088674 /**< RX FIFO pointer */
#define RFCORE_XREG_RXLAST_PTR 0x40088678 /**< RX FIFO pointer */
#define RFCORE_XREG_RXP1_PTR 0x4008867C /**< RX FIFO pointer */
#define RFCORE_XREG_RXP2_PTR 0x40088680 /**< RX FIFO pointer */
#define RFCORE_XREG_TXFIRST_PTR 0x40088684 /**< TX FIFO pointer */
#define RFCORE_XREG_TXLAST_PTR 0x40088688 /**< TX FIFO pointer */
#define RFCORE_XREG_RFIRQM0 0x4008868C /**< RF interrupt masks */
#define RFCORE_XREG_RFIRQM1 0x40088690 /**< RF interrupt masks */
#define RFCORE_XREG_RFERRM 0x40088694 /**< RF error interrupt mask */
#define RFCORE_XREG_D18_SPARE_OPAMPMC 0x40088698 /**< Operational amp mode ctrl */
#define RFCORE_XREG_RFRND 0x4008869C /**< Random data */
#define RFCORE_XREG_MDMCTRL0 0x400886A0 /**< Controls modem */
#define RFCORE_XREG_MDMCTRL1 0x400886A4 /**< Controls modem */
#define RFCORE_XREG_FREQEST 0x400886A8 /**< Estimated RF frequency offset */
#define RFCORE_XREG_RXCTRL 0x400886AC /**< Tune receive section */
#define RFCORE_XREG_FSCTRL 0x400886B0 /**< Tune frequency synthesizer */
#define RFCORE_XREG_FSCAL1 0x400886B8 /**< Tune frequency calibration */
#define RFCORE_XREG_FSCAL2 0x400886BC /**< Tune frequency calibration */
#define RFCORE_XREG_FSCAL3 0x400886C0 /**< Tune frequency calibration */
#define RFCORE_XREG_AGCCTRL0 0x400886C4 /**< AGC dynamic range control */
#define RFCORE_XREG_AGCCTRL1 0x400886C8 /**< AGC reference level */
#define RFCORE_XREG_AGCCTRL2 0x400886CC /**< AGC gain override */
#define RFCORE_XREG_AGCCTRL3 0x400886D0 /**< AGC control */
#define RFCORE_XREG_ADCTEST0 0x400886D4 /**< ADC tuning */
#define RFCORE_XREG_ADCTEST1 0x400886D8 /**< ADC tuning */
#define RFCORE_XREG_ADCTEST2 0x400886DC /**< ADC tuning */
#define RFCORE_XREG_MDMTEST0 0x400886E0 /**< Test register for modem */
#define RFCORE_XREG_MDMTEST1 0x400886E4 /**< Test Register for Modem */
#define RFCORE_XREG_DACTEST0 0x400886E8 /**< DAC override value */
#define RFCORE_XREG_DACTEST1 0x400886EC /**< DAC override value */
#define RFCORE_XREG_DACTEST2 0x400886F0 /**< DAC test setting */
#define RFCORE_XREG_ATEST 0x400886F4 /**< Analog test control */
#define RFCORE_XREG_PTEST0 0x400886F8 /**< Override power-down register */
#define RFCORE_XREG_PTEST1 0x400886FC /**< Override power-down register */
#define RFCORE_XREG_CSPPROG0 0x40088700 /**< CSP program */
#define RFCORE_XREG_CSPPROG1 0x40088704 /**< CSP program */
#define RFCORE_XREG_CSPPROG2 0x40088708 /**< CSP program */
#define RFCORE_XREG_CSPPROG3 0x4008870C /**< CSP program */
#define RFCORE_XREG_CSPPROG4 0x40088710 /**< CSP program */
#define RFCORE_XREG_CSPPROG5 0x40088714 /**< CSP program */
#define RFCORE_XREG_CSPPROG6 0x40088718 /**< CSP program */
#define RFCORE_XREG_CSPPROG7 0x4008871C /**< CSP program */
#define RFCORE_XREG_CSPPROG8 0x40088720 /**< CSP program */
#define RFCORE_XREG_CSPPROG9 0x40088724 /**< CSP program */
#define RFCORE_XREG_CSPPROG10 0x40088728 /**< CSP program */
#define RFCORE_XREG_CSPPROG11 0x4008872C /**< CSP program */
#define RFCORE_XREG_CSPPROG12 0x40088730 /**< CSP program */
#define RFCORE_XREG_CSPPROG13 0x40088734 /**< CSP program */
#define RFCORE_XREG_CSPPROG14 0x40088738 /**< CSP program */
#define RFCORE_XREG_CSPPROG15 0x4008873C /**< CSP program */
#define RFCORE_XREG_CSPPROG16 0x40088740 /**< CSP program */
#define RFCORE_XREG_CSPPROG17 0x40088744 /**< CSP program */
#define RFCORE_XREG_CSPPROG18 0x40088748 /**< CSP program */
#define RFCORE_XREG_CSPPROG19 0x4008874C /**< CSP program */
#define RFCORE_XREG_CSPPROG20 0x40088750 /**< CSP program */
#define RFCORE_XREG_CSPPROG21 0x40088754 /**< CSP program */
#define RFCORE_XREG_CSPPROG22 0x40088758 /**< CSP program */
#define RFCORE_XREG_CSPPROG23 0x4008875C /**< CSP program */
#define RFCORE_XREG_CSPCTRL 0x40088780 /**< CSP control bit */
#define RFCORE_XREG_CSPSTAT 0x40088784 /**< CSP status register */
#define RFCORE_XREG_CSPX 0x40088788 /**< CSP X data register */
#define RFCORE_XREG_CSPY 0x4008878C /**< CSP Y data register */
#define RFCORE_XREG_CSPZ 0x40088790 /**< CSP Z data register */
#define RFCORE_XREG_CSPT 0x40088794 /**< CSP T data register */
#define RFCORE_XREG_RFC_DUTY_CYCLE 0x400887A0 /**< RX duty cycle control */
#define RFCORE_XREG_RFC_OBS_CTRL0 0x400887AC /**< RF observation mux control */
#define RFCORE_XREG_RFC_OBS_CTRL1 0x400887B0 /**< RF observation mux control */
#define RFCORE_XREG_RFC_OBS_CTRL2 0x400887B4 /**< RF observation mux control */
#define RFCORE_XREG_TXFILTCFG 0x400887E8 /**< TX filter configuration */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_FRMFILT0 register offsets
* @{
*/
#define RFCORE_XREG_FRMFILT0_MAX_FRAME_VERSION 0x0000000C /**< Frame version filtering */
#define RFCORE_XREG_FRMFILT0_PAN_COORDINATOR 0x00000002 /**< PAN coordinator */
#define RFCORE_XREG_FRMFILT0_FRAME_FILTER_EN 0x00000001 /**< Enables frame filtering */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_FRMFILT1 register offsets
* @{
*/
#define RFCORE_XREG_FRMFILT1_ACCEPT_FT_3_MAC_CMD 0x00000040 /**< MAC command frame filt */
#define RFCORE_XREG_FRMFILT1_ACCEPT_FT_2_ACK 0x00000020 /**< ack frame filt */
#define RFCORE_XREG_FRMFILT1_ACCEPT_FT_1_DATA 0x00000010 /**< data frame filt */
#define RFCORE_XREG_FRMFILT1_ACCEPT_FT_0_BEACON 0x00000008 /**< beacon frame filt */
#define RFCORE_XREG_FRMFILT1_MODIFY_FT_FILTER 0x00000006 /**< Frame type modify */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_SRCMATCH register bit masks
* @{
*/
#define RFCORE_XREG_SRCMATCH_PEND_DATAREQ_ONLY 0x00000004 /**< AUTOPEND function */
#define RFCORE_XREG_SRCMATCH_AUTOPEND 0x00000002 /**< Automatic acknowledgment */
#define RFCORE_XREG_SRCMATCH_SRC_MATCH_EN 0x00000001 /**< Source address matching enable */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_SRCSHORTEN0 register bit masks
* @{
*/
#define RFCORE_XREG_SRCSHORTEN0_SHORT_ADDR_EN 0x000000FF /**< SHORT_ADDR_EN[7:0] */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_SRCSHORTEN1 register bit masks
* @{
*/
#define RFCORE_XREG_SRCSHORTEN1_SHORT_ADDR_EN 0x000000FF /**< SHORT_ADDR_EN[15:8] */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_SRCSHORTEN2 register bit masks
* @{
*/
#define RFCORE_XREG_SRCSHORTEN2_SHORT_ADDR_EN 0x000000FF /**< SHORT_ADDR_EN[23:16] */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_SRCEXTEN0 register bit masks
* @{
*/
#define RFCORE_XREG_SRCEXTEN0_EXT_ADDR_EN 0x000000FF /**< EXT_ADDR_EN[7:0] */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_SRCEXTEN1 register bit masks
* @{
*/
#define RFCORE_XREG_SRCEXTEN1_EXT_ADDR_EN 0x000000FF /**< EXT_ADDR_EN[15:8] */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_SRCEXTEN2 register bit masks
* @{
*/
#define RFCORE_XREG_SRCEXTEN2_EXT_ADDR_EN 0x000000FF /**< EXT_ADDR_EN[23:16] */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_FRMCTRL0 register bit masks
* @{
*/
#define RFCORE_XREG_FRMCTRL0_APPEND_DATA_MODE 0x00000080 /**< Append data mode */
#define RFCORE_XREG_FRMCTRL0_AUTOCRC 0x00000040 /**< Auto CRC generation / checking */
#define RFCORE_XREG_FRMCTRL0_AUTOACK 0x00000020 /**< Transmit ACK frame enable */
#define RFCORE_XREG_FRMCTRL0_ENERGY_SCAN 0x00000010 /**< RSSI register content control */
#define RFCORE_XREG_FRMCTRL0_RX_MODE 0x0000000C /**< Set RX modes */
#define RFCORE_XREG_FRMCTRL0_TX_MODE 0x00000003 /**< Set test modes for TX */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_FRMCTRL1 register bit masks
* @{
*/
#define RFCORE_XREG_FRMCTRL1_PENDING_OR 0x00000004 /**< Pending data bit control */
#define RFCORE_XREG_FRMCTRL1_IGNORE_TX_UNDERF 0x00000002 /**< TX underflow ignore */
#define RFCORE_XREG_FRMCTRL1_SET_RXENMASK_ON_TX 0x00000001 /**< RXENABLE control */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_RXENABLE register bit masks
* @{
*/
#define RFCORE_XREG_RXENABLE_RXENMASK 0x000000FF /**< Enables the receiver. */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_RXMASKSET register bit masks
* @{
*/
#define RFCORE_XREG_RXMASKSET_RXENMASKSET 0x000000FF /**< Write to RXENMASK (OR) */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_RXMASKCLR register bit masks
* @{
*/
#define RFCORE_XREG_RXMASKCLR_RXENMASKCLR 0x000000FF /**< RXENMASK clear bits */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_FREQTUNE register bit masks
* @{
*/
#define RFCORE_XREG_FREQTUNE_XOSC32M_TUNE 0x0000000F /**< Tune crystal oscillator */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_FREQCTRL register bit masks
* @{
*/
#define RFCORE_XREG_FREQCTRL_FREQ 0x0000007F /**< Frequency control word */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_TXPOWER register bit masks
* @{
*/
#define RFCORE_XREG_TXPOWER_PA_POWER 0x000000F0 /**< PA power control */
#define RFCORE_XREG_TXPOWER_PA_BIAS 0x0000000F /**< PA bias control */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_TXCTRL register bit masks
* @{
*/
#define RFCORE_XREG_TXCTRL_DAC_CURR 0x00000070 /**< Change the current in the DAC. */
#define RFCORE_XREG_TXCTRL_DAC_DC 0x0000000C /**< Adjusts the DC level to the TX mixer */
#define RFCORE_XREG_TXCTRL_TXMIX_CURRENT 0x00000003 /**< TX mixer core current */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_FSMSTAT0 register bit masks
* @{
*/
#define RFCORE_XREG_FSMSTAT0_CAL_DONE 0x00000080 /**< Calib has been performed */
#define RFCORE_XREG_FSMSTAT0_CAL_RUNNING 0x00000040 /**< Calib status */
#define RFCORE_XREG_FSMSTAT0_FSM_FFCTRL_STATE 0x0000003F /**< FIFO and FFCTRL status */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_FSMSTAT1 register bit masks
* @{
*/
#define RFCORE_XREG_FSMSTAT1_FIFO 0x00000080 /**< FIFO status */
#define RFCORE_XREG_FSMSTAT1_FIFOP 0x00000040 /**< FIFOP status */
#define RFCORE_XREG_FSMSTAT1_SFD 0x00000020 /**< SFD was sent/received */
#define RFCORE_XREG_FSMSTAT1_CCA 0x00000010 /**< Clear channel assessment */
#define RFCORE_XREG_FSMSTAT1_SAMPLED_CCA 0x00000008 /**< CCA sample value */
#define RFCORE_XREG_FSMSTAT1_LOCK_STATUS 0x00000004 /**< PLL lock status */
#define RFCORE_XREG_FSMSTAT1_TX_ACTIVE 0x00000002 /**< Status signal - TX states */
#define RFCORE_XREG_FSMSTAT1_RX_ACTIVE 0x00000001 /**< Status signal - RX states */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_FIFOPCTRL register bit masks
* @{
*/
#define RFCORE_XREG_FIFOPCTRL_FIFOP_THR 0x0000007F /**< FIFOP signal threshold */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_FSMCTRL register bit masks
* @{
*/
#define RFCORE_XREG_FSMCTRL_SLOTTED_ACK 0x00000002 /**< ACK frame TX timing */
#define RFCORE_XREG_FSMCTRL_RX2RX_TIME_OFF 0x00000001 /**< 12-sym timeout after RX */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_CCACTRL0 register bit masks
* @{
*/
#define RFCORE_XREG_CCACTRL0_CCA_THR 0x000000FF /**< Clear-channel-assessment */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_CCACTRL1 register bit masks
* @{
*/
#define RFCORE_XREG_CCACTRL1_CCA_MODE 0x00000018 /**< CCA mode */
#define RFCORE_XREG_CCACTRL1_CCA_HYST 0x00000007 /**< CCA hysteresis */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_RSSI register bit masks
* @{
*/
#define RFCORE_XREG_RSSI_RSSI_VAL 0x000000FF /**< RSSI estimate */
#define RFCORE_XREG_RSSI_RSSI_VAL_S 0
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_RSSISTAT register bit masks
* @{
*/
#define RFCORE_XREG_RSSISTAT_RSSI_VALID 0x00000001 /**< RSSI value is valid */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_RXFIRST register bit masks
* @{
*/
#define RFCORE_XREG_RXFIRST_DATA 0x000000FF /**< First byte of the RX FIFO */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_RXFIFOCNT register bit masks
* @{
*/
#define RFCORE_XREG_RXFIFOCNT_RXFIFOCNT 0x000000FF /**< Number of bytes in the RX FIFO */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_TXFIFOCNT register bit masks
* @{
*/
#define RFCORE_XREG_TXFIFOCNT_TXFIFOCNT 0x000000FF /**< Number of bytes in the TX FIFO */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RX FIFO pointers
* @{
*/
#define RFCORE_XREG_RXFIRST_PTR_RXFIRST_PTR 0x000000FF /**< Byte 1 */
#define RFCORE_XREG_RXLAST_PTR_RXLAST_PTR 0x000000FF /**< Last byte + 1 */
#define RFCORE_XREG_RXP1_PTR_RXP1_PTR 0x000000FF /**< Frame 1, byte 1 */
#define RFCORE_XREG_RXP2_PTR_RXP2_PTR 0x000000FF /**< Last frame, byte 1 */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name TX FIFO pointers
* @{
*/
#define RFCORE_XREG_TXFIRST_PTR_TXFIRST_PTR 0x000000FF /**< Next byte to be TXd */
#define RFCORE_XREG_TXLAST_PTR_TXLAST_PTR 0x000000FF /**< Last byte + 1 */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_RFIRQM0 register bit masks
* @{
*/
#define RFCORE_XREG_RFIRQM0_RFIRQM 0x000000FF /**< Interrupt source bit mask */
#define RFCORE_XREG_RFIRQM0_RXMASKZERO 0x00000080 /**< RXENABLE gone all-zero */
#define RFCORE_XREG_RFIRQM0_RXPKTDONE 0x00000040 /**< Complete frame RX */
#define RFCORE_XREG_RFIRQM0_FRAME_ACCEPTED 0x00000020 /**< Frame has passed frame filter */
#define RFCORE_XREG_RFIRQM0_SRC_MATCH_FOUND 0x00000010 /**< Source match is found */
#define RFCORE_XREG_RFIRQM0_SRC_MATCH_DONE 0x00000008 /**< Source matching is complete */
#define RFCORE_XREG_RFIRQM0_FIFOP 0x00000004 /**< RX FIFO exceeded threshold */
#define RFCORE_XREG_RFIRQM0_SFD 0x00000002 /**< SFD TX or RX */
#define RFCORE_XREG_RFIRQM0_ACT_UNUSED 0x00000001 /**< Reserved */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_RFIRQM1 register bit masks
* @{
*/
#define RFCORE_XREG_RFIRQM1_RFIRQM 0x0000003F /**< Interrupt source bit mask */
#define RFCORE_XREG_RFIRQM1_CSP_WAIT 0x00000020 /**< CSP Execution continued */
#define RFCORE_XREG_RFIRQM1_CSP_STOP 0x00000010 /**< CSP has stopped program */
#define RFCORE_XREG_RFIRQM1_CSP_MANINT 0x00000008 /**< CSP Manual interrupt */
#define RFCORE_XREG_RFIRQM1_RFIDLE 0x00000004 /**< IDLE state entered */
#define RFCORE_XREG_RFIRQM1_TXDONE 0x00000002 /**< Complete frame TX finished */
#define RFCORE_XREG_RFIRQM1_TXACKDONE 0x00000001 /**< ACK frame TX finished */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_RFERRM register bit masks
* @{
*/
#define RFCORE_XREG_RFERRM_RFERRM 0x0000007F /**< RF error interrupt mask */
#define RFCORE_XREG_RFERRM_STROBEERR 0x00000040 /**< Strobe error */
#define RFCORE_XREG_RFERRM_TXUNDERF 0x00000020 /**< TX FIFO underflowed */
#define RFCORE_XREG_RFERRM_TXOVERF 0x00000010 /**< TX FIFO overflowed */
#define RFCORE_XREG_RFERRM_RXUNDERF 0x00000008 /**< RX FIFO underflowed */
#define RFCORE_XREG_RFERRM_RXOVERF 0x00000004 /**< RX FIFO overflowed */
#define RFCORE_XREG_RFERRM_RXABO 0x00000002 /**< Frame RX was aborted */
#define RFCORE_XREG_RFERRM_NLOCK 0x00000001 /**< Frequency synthesizer lock error */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_D18_SPARE_OPAMPMC register bit masks
* @{
*/
#define RFCORE_XREG_D18_SPARE_OPAMPMC_MODE 0x00000003 /**< Operational amplifier mode */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_RFRND register bit masks
* @{
*/
#define RFCORE_XREG_RFRND_QRND 0x00000002 /**< Random bit from the Q channel */
#define RFCORE_XREG_RFRND_IRND 0x00000001 /**< Random bit from the I channel */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_MDMCTRL0 register bit masks
* @{
*/
#define RFCORE_XREG_MDMCTRL0_DEM_NUM_ZEROS 0x000000C0 /**< Num of zero symbols before sync word */
#define RFCORE_XREG_MDMCTRL0_DEMOD_AVG_MODE 0x00000020 /**< Frequency offset averaging filter */
#define RFCORE_XREG_MDMCTRL0_PREAMBLE_LENGTH 0x0000001E /**< Number of preamble bytes */
#define RFCORE_XREG_MDMCTRL0_TX_FILTER 0x00000001 /**< TX filter type */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_MDMCTRL1 register bit masks
* @{
*/
#define RFCORE_XREG_MDMCTRL1_CORR_THR_SFD 0x00000020 /**< SFD detection requirements */
#define RFCORE_XREG_MDMCTRL1_CORR_THR 0x0000001F /**< Demodulator correlator threshold */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_FREQEST register bit masks
* @{
*/
#define RFCORE_XREG_FREQEST_FREQEST 0x000000FF
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_RXCTRL register bit masks
* @{
*/
#define RFCORE_XREG_RXCTRL_GBIAS_LNA2_REF 0x00000030 /**< LNA2/mixer PTAT current output */
#define RFCORE_XREG_RXCTRL_GBIAS_LNA_REF 0x0000000C /**< LNA PTAT current output */
#define RFCORE_XREG_RXCTRL_MIX_CURRENT 0x00000003 /**< Control of the output current */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_FSCTRL register bit masks
* @{
*/
#define RFCORE_XREG_FSCTRL_PRE_CURRENT 0x000000C0 /**< Prescaler current setting */
#define RFCORE_XREG_FSCTRL_LODIV_BUF_CURRENT_TX 0x00000030 /**< Adjusts current in mixer and PA adjust */
#define RFCORE_XREG_FSCTRL_LODIV_BUF_CURRENT_RX 0x0000000C /**< Adjusts current in mixer and PA adjust */
#define RFCORE_XREG_FSCTRL_LODIV_CURRENT 0x00000003 /**< Adjusts divider currents */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_FSCAL1 register bit masks
* @{
*/
#define RFCORE_XREG_FSCAL1_VCO_CURR_CAL_OE 0x00000080 /**< Override current calibration */
#define RFCORE_XREG_FSCAL1_VCO_CURR_CAL 0x0000007C /**< Calibration result */
#define RFCORE_XREG_FSCAL1_VCO_CURR 0x00000003 /**< Defines current in VCO core */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_FSCAL2 register bit masks
* @{
*/
#define RFCORE_XREG_FSCAL2_VCO_CAPARR_OE 0x00000040 /**< Override the calibration result */
#define RFCORE_XREG_FSCAL2_VCO_CAPARR 0x0000003F /**< VCO capacitor array setting */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_FSCAL3 register bit masks
* @{
*/
#define RFCORE_XREG_FSCAL3_VCO_DAC_EN_OV 0x00000040 /**< VCO DAC Enable */
#define RFCORE_XREG_FSCAL3_VCO_VC_DAC 0x0000003C /**< Varactor control voltage Bit vector */
#define RFCORE_XREG_FSCAL3_VCO_CAPARR_CAL_CTRL 0x00000003 /**< Calibration accuracy setting */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_AGCCTRL0 register bit masks
* @{
*/
#define RFCORE_XREG_AGCCTRL0_AGC_DR_XTND_EN 0x00000040 /**< AAF attenuation adjustment */
#define RFCORE_XREG_AGCCTRL0_AGC_DR_XTND_THR 0x0000003F /**< Enable extra attenuation in front end */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_AGCCTRL1 register bit masks
* @{
*/
#define RFCORE_XREG_AGCCTRL1_AGC_REF 0x0000003F /**< Target value for the AGC control loop */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_AGCCTRL2 register bit masks
* @{
*/
#define RFCORE_XREG_AGCCTRL2_LNA1_CURRENT 0x000000C0 /**< Overrride value for LNA 1 */
#define RFCORE_XREG_AGCCTRL2_LNA2_CURRENT 0x00000038 /**< Overrride value for LNA 2 */
#define RFCORE_XREG_AGCCTRL2_LNA3_CURRENT 0x00000006 /**< Overrride value for LNA 3 */
#define RFCORE_XREG_AGCCTRL2_LNA_CURRENT_OE 0x00000001 /**< AGC LNA override */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_AGCCTRL3 register bit masks
* @{
*/
#define RFCORE_XREG_AGCCTRL3_AGC_SETTLE_WAIT 0x00000060 /**< AGC analog gain wait */
#define RFCORE_XREG_AGCCTRL3_AGC_WIN_SIZE 0x00000018 /**< AGC accumulate-and-dump window size */
#define RFCORE_XREG_AGCCTRL3_AAF_RP 0x00000006 /**< AGC to AAF control signal override */
#define RFCORE_XREG_AGCCTRL3_AAF_RP_OE 0x00000001 /**< AAF control signal override */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_ADCTEST0 register bit masks
* @{
*/
#define RFCORE_XREG_ADCTEST0_ADC_VREF_ADJ 0x000000C0 /**< Quantizer threshold control */
#define RFCORE_XREG_ADCTEST0_ADC_QUANT_ADJ 0x00000030 /**< Quantizer threshold control */
#define RFCORE_XREG_ADCTEST0_ADC_GM_ADJ 0x0000000E /**< Gm-control for test and debug */
#define RFCORE_XREG_ADCTEST0_ADC_DAC2_EN 0x00000001 /**< Enables DAC2 */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_ADCTEST1 register bit masks
* @{
*/
#define RFCORE_XREG_ADCTEST1_ADC_TEST_CTRL 0x000000F0 /**< ADC test mode selector */
#define RFCORE_XREG_ADCTEST1_ADC_C2_ADJ 0x0000000C /**< ADC capacitor value adjust */
#define RFCORE_XREG_ADCTEST1_ADC_C3_ADJ 0x00000003 /**< ADC capacitor value adjust */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_ADCTEST2 register bit masks
* @{
*/
#define RFCORE_XREG_ADCTEST2_ADC_TEST_MODE 0x00000060 /**< ADC data output test mode */
#define RFCORE_XREG_ADCTEST2_AAF_RS 0x00000018 /**< AAF series resistance control */
#define RFCORE_XREG_ADCTEST2_ADC_FF_ADJ 0x00000006 /**< Adjust feed forward */
#define RFCORE_XREG_ADCTEST2_ADC_DAC_ROT 0x00000001 /**< Control of DAC DWA scheme */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_MDMTEST0 register bit masks
* @{
*/
#define RFCORE_XREG_MDMTEST0_TX_TONE 0x000000F0 /**< Baseband tone TX enable */
#define RFCORE_XREG_MDMTEST0_DC_WIN_SIZE 0x0000000C /**< Controls the numbers of samples */
#define RFCORE_XREG_MDMTEST0_DC_BLOCK_MODE 0x00000003 /**< Mode of operation select */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_MDMTEST1 register bit masks
* @{
*/
#define RFCORE_XREG_MDMTEST1_USEMIRROR_IF 0x00000020 /**< IF frequency select */
#define RFCORE_XREG_MDMTEST1_MOD_IF 0x00000010 /**< Modulation select */
#define RFCORE_XREG_MDMTEST1_RAMP_AMP 0x00000008 /**< Ramping of DAC output enable */
#define RFCORE_XREG_MDMTEST1_RFC_SNIFF_EN 0x00000004 /**< Packet sniffer module enable */
#define RFCORE_XREG_MDMTEST1_MODULATION_MODE 0x00000002 /**< RF-modulation mode */
#define RFCORE_XREG_MDMTEST1_LOOPBACK_EN 0x00000001 /**< Modulated data loopback enable */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_DACTEST0 register bit masks
* @{
*/
#define RFCORE_XREG_DACTEST0_DAC_Q 0x400886FF /**< Q-branch DAC override value */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_DACTEST1 register bit masks
* @{
*/
#define RFCORE_XREG_DACTEST1_DAC_I 0x400886FF /**< I-branch DAC override value */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_DACTEST2 register bit masks
* @{
*/
#define RFCORE_XREG_DACTEST2_DAC_DEM_EN 0x00000020 /**< Dynamic element matching enable */
#define RFCORE_XREG_DACTEST2_DAC_CASC_CTRL 0x00000018 /**< Adjustment of output stage */
#define RFCORE_XREG_DACTEST2_DAC_SRC 0x00000007 /**< TX DAC data src select */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_ATEST register bit masks
* @{
*/
#define RFCORE_XREG_ATEST_ATEST_CTRL 0x0000003F /**< Controls the analog test mode */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_PTEST0 register bit masks
* @{
*/
#define RFCORE_XREG_PTEST0_PRE_PD 0x00000080 /**< Prescaler power-down signal */
#define RFCORE_XREG_PTEST0_CHP_PD 0x00000040 /**< Charge pump power-down signal */
#define RFCORE_XREG_PTEST0_ADC_PD 0x00000020 /**< ADC power-down signal When */
#define RFCORE_XREG_PTEST0_DAC_PD 0x00000010 /**< DAC power-down signal When */
#define RFCORE_XREG_PTEST0_LNA_PD 0x0000000C /**< Low-noise amplifier power-down */
#define RFCORE_XREG_PTEST0_TXMIX_PD 0x00000002 /**< Transmit mixer power-down */
#define RFCORE_XREG_PTEST0_AAF_PD 0x00000001 /**< Antialiasing filter power-down */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_PTEST1 register bit masks
* @{
*/
#define RFCORE_XREG_PTEST1_PD_OVERRIDE 0x00000008 /**< Override module enabling and disabling */
#define RFCORE_XREG_PTEST1_PA_PD 0x00000004 /**< Power amplifier power-down signal */
#define RFCORE_XREG_PTEST1_VCO_PD 0x00000002 /**< VCO power-down signal */
#define RFCORE_XREG_PTEST1_LODIV_PD 0x00000001 /**< LO power-down signal */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_CSPPROG[0:24] register bit masks
* @{
*/
#define RFCORE_XREG_CSPPROG_CSP_INSTR 0x000000FF /**< Byte N of the CSP program */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_CSPCTRL register bit masks
* @{
*/
#define RFCORE_XREG_CSPCTRL_MCU_CTRL 0x00000001 /**< CSP MCU control input */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_CSPSTAT register bit masks
* @{
*/
#define RFCORE_XREG_CSPSTAT_CSP_RUNNING 0x00000020 /**< CSP Running / Idle */
#define RFCORE_XREG_CSPSTAT_CSP_PC 0x0000001F /**< CSP program counter */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_CSPX register bit masks
* @{
*/
#define RFCORE_XREG_CSPX_CSPX 0x000000FF /**< CSP X data */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_CSPY register bit masks
* @{
*/
#define RFCORE_XREG_CSPY_CSPY 0x000000FF /**< CSP Y data */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_CSPZ register bit masks
* @{
*/
#define RFCORE_XREG_CSPZ_CSPZ 0x000000FF /**< CSP Z data */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_CSPT register bit masks
* @{
*/
#define RFCORE_XREG_CSPT_CSPT 0x000000FF /**< CSP T data */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_RFC_DUTY_CYCLE register bit masks
* @{
*/
#define RFCORE_XREG_RFC_DUTY_CYCLE_SWD_EN 0x00000040 /**< Wire debug mode */
#define RFCORE_XREG_RFC_DUTY_CYCLE_DTC_DCCAL_MODE 0x00000030 /**< Periodic DC-recalibration mode */
#define RFCORE_XREG_RFC_DUTY_CYCLE_DUTYCYCLE_CNF 0x0000000E /**< Defines duty cycling */
#define RFCORE_XREG_RFC_DUTY_CYCLE_DUTYCYCLE_EN 0x00000001 /**< Duty cycling mode enable */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_RFC_OBS_CTRL[0:2] register bit masks
* @{
*/
#define RFCORE_XREG_RFC_OBS_CTRL0_RFC_OBS_POL0 0x00000040 /**< RFC_OBS_MUX0 XOR bit */
#define RFCORE_XREG_RFC_OBS_CTRL0_RFC_OBS_MUX0 0x0000003F /**< RF Core MUX out control */
#define RFCORE_XREG_RFC_OBS_CTRL1_RFC_OBS_POL1 0x00000040 /**< RFC_OBS_MUX0 XOR bit */
#define RFCORE_XREG_RFC_OBS_CTRL1_RFC_OBS_MUX1 0x0000003F /**< RF Core MUX out control */
#define RFCORE_XREG_RFC_OBS_CTRL2_RFC_OBS_POL2 0x00000040 /**< RFC_OBS_MUX0 XOR bit */
#define RFCORE_XREG_RFC_OBS_CTRL2_RFC_OBS_MUX2 0x0000003F /**< RF Core MUX out control */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_TXFILTCFG register bit masks
* @{
*/
#define RFCORE_XREG_TXFILTCFG_FC 0x0000000F /**< Drives signal rfr_txfilt_fc */
/** @} */
#endif /* RFCORE_XREG_H_ */
/** @} */

57
cpu/cc2538/dev/rfcore.h Normal file
View File

@ -0,0 +1,57 @@
/*
* 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 cc2538
* @{
*
* \defgroup cc2538-rfcore cc2538 RF Core
*
* Declarations of RF Core registers. Includes SFR, XREG and FFSM
* @{
*
* \file
* Top-level header file for cc2538 RF Core registers. Includes the files
* where the actual declarations reside
*/
#ifndef RFCORE_H_
#define RFCORE_H_
#include "dev/rfcore-ffsm.h"
#include "dev/rfcore-xreg.h"
#include "dev/rfcore-sfr.h"
#include "dev/ana-regs.h"
#endif /* RFCORE_H_ */
/**
* @}
* @}
*/

81
cpu/cc2538/dev/scb.h Normal file
View File

@ -0,0 +1,81 @@
/*
* 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 cc2538
* @{
*
* \defgroup cc2538-scb cc2538 System Control Block
* @{
*
* \file
* Header file for the System Control Block (SCB)
*/
#ifndef SCB_H_
#define SCB_H_
#define SCB_CPUID 0xE000ED00 /**< CPU ID Base */
#define SCB_INTCTRL 0xE000ED04 /**< Interrupt Control and State */
#define SCB_VTABLE 0xE000ED08 /**< Vector Table Offset */
#define SCB_APINT 0xE000ED0C /**< Application Interrupt and Reset Control */
#define SCB_SYSCTRL 0xE000ED10 /**< System Control */
#define SCB_CFGCTRL 0xE000ED14 /**< Configuration and Control */
#define SCB_SYSPRI1 0xE000ED18 /**< System Handler Priority 1 */
#define SCB_SYSPRI2 0xE000ED1C /**< System Handler Priority 2 */
#define SCB_SYSPRI3 0xE000ED20 /**< System Handler Priority 3 */
#define SCB_SYSHNDCTRL 0xE000ED24 /**< System Handler Control and State */
#define SCB_FAULTSTAT 0xE000ED28 /**< Configurable Fault Status */
#define SCB_HFAULTSTAT 0xE000ED2C /**< Hard Fault Status */
#define SCB_DEBUG_STAT 0xE000ED30 /**< Debug Status Register */
#define SCB_MMADDR 0xE000ED34 /**< Memory Management Fault Address */
#define SCB_FAULT_ADDR 0xE000ED38 /**< Bus Fault Address */
/*---------------------------------------------------------------------------*/
/** \name VTABLE register bits
* @{
*/
#define SCB_VTABLE_BASE 0x20000000 /**< Vector Table Base */
#define SCB_VTABLE_OFFSET_M 0x1FFFFE00 /**< Vector Table Offset */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SCB_SYSCTRL register bits
* @{
*/
#define SCB_SYSCTRL_SEVONPEND 0x00000010 /**< Wake up on pending */
#define SCB_SYSCTRL_SLEEPDEEP 0x00000004 /**< Deep sleep enable */
#define SCB_SYSCTRL_SLEEPEXIT 0x00000002 /**< Sleep on ISR exit */
/** @} */
/*---------------------------------------------------------------------------*/
#endif /* SCB_H_ */
/**
* @}
* @}
*/

119
cpu/cc2538/dev/smwdthrosc.h Normal file
View File

@ -0,0 +1,119 @@
/*
* 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 cc2538
* @{
*
* \defgroup cc2538-smwdthrosc cc2538 Sleep Timer and Watchdog
*
* Register declarations for the cc2538 Sleep Timer and Watchdog
* @{
*
* \file
* Header file with register declarations and bit masks for the cc2538
* Sleep Timer and Watchdog
*/
#ifndef SMWDTHROSC_H_
#define SMWDTHROSC_H_
/*---------------------------------------------------------------------------*/
/** \name ST and WDT Register offset declarations
* @{
*/
#define SMWDTHROSC_WDCTL 0x400D5000 /**< Watchdog Control */
#define SMWDTHROSC_ST0 0x400D5040 /**< ST count/compare value 0 */
#define SMWDTHROSC_ST1 0x400D5044 /**< ST count/compare value 1 */
#define SMWDTHROSC_ST2 0x400D5048 /**< ST count/compare value 2 */
#define SMWDTHROSC_ST3 0x400D504C /**< ST count/compare value 3 */
#define SMWDTHROSC_STLOAD 0x400D5050 /**< Compare value load status */
#define SMWDTHROSC_STCC 0x400D5054 /**< ST capture control */
#define SMWDTHROSC_STCS 0x400D5058 /**< ST capture status */
#define SMWDTHROSC_STCV0 0x400D505C /**< ST capture value 0 */
#define SMWDTHROSC_STCV1 0x400D5060 /**< ST capture value 1 */
#define SMWDTHROSC_STCV2 0x400D5064 /**< ST capture value 2 */
#define SMWDTHROSC_STCV3 0x400D5068 /**< ST capture value 3 */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SMWDTHROSC_WDCTL register bit masks
* @{
*/
#define SMWDTHROSC_WDCTL_CLR 0x000000F0 /**< Clear timer mask */
#define SMWDTHROSC_WDCTL_CLR_3 0x00000080 /**< Clear timer mask[3] */
#define SMWDTHROSC_WDCTL_CLR_2 0x00000040 /**< Clear timer mask[2] */
#define SMWDTHROSC_WDCTL_CLR_1 0x00000020 /**< Clear timer mask[1] */
#define SMWDTHROSC_WDCTL_CLR_0 0x00000010 /**< Clear timer mask[0] */
#define SMWDTHROSC_WDCTL_EN 0x00000008 /**< Enable mask */
#define SMWDTHROSC_WDCTL_MODE 0x00000004 /**< Mode select mask */
#define SMWDTHROSC_WDCTL_INT 0x00000003 /**< Interval Select mask */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SMWDTHROSC_ST[0:3] register bit masks
* @{
*/
#define SMWDTHROSC_ST0_ST0 0x000000FF /**< ST count/compare bits [7:0] */
#define SMWDTHROSC_ST1_ST1 0x000000FF /**< ST count/compare bits [15:8] */
#define SMWDTHROSC_ST2_ST2 0x000000FF /**< ST count/compare bits [23:16] */
#define SMWDTHROSC_ST3_ST3 0x000000FF /**< ST count/compare bits [31:24] */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SMWDTHROSC_STLOAD register bit masks
* @{
*/
#define SMWDTHROSC_STLOAD_STLOAD 0x00000001 /**< STx upload status signal */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SMWDTHROSC_STCC register bit masks
* @{
*/
#define SMWDTHROSC_STCC_PORT 0x00000038 /**< Port select */
#define SMWDTHROSC_STCC_PIN 0x00000007 /**< Pin select */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SMWDTHROSC_STCS register bit masks
* @{
*/
#define SMWDTHROSC_STCS_VALID 0x00000001 /**< Capture valid flag */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SMWDTHROSC_STCV[0:3] register bit masks
* @{
*/
#define SMWDTHROSC_STCV0_STCV0 0x000000FF /**< ST capture bits [7:0] */
#define SMWDTHROSC_STCV1_STCV1 0x000000FF /**< ST capture bits [15:8] */
#define SMWDTHROSC_STCV2_STCV2 0x000000FF /**< ST capture bits [23:16] */
#define SMWDTHROSC_STCV3_STCV3 0x000000FF /**< ST capture bits [32:24] */
/** @} */
#endif /* SMWDTHROSC_H_ */
/**
* @}
* @}
*/

112
cpu/cc2538/dev/soc-adc.h Normal file
View File

@ -0,0 +1,112 @@
/*
* 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 cc2538
* @{
*
* \defgroup cc2538-soc-adc cc2538 ADC and RNG
*
* Register declarations for the cc2538 ADC and H/W RNG
* @{
*
* \file
* Header file with register declarations for the cc2538 ADC and H/W RNG
*/
#ifndef SOC_ADC_H_
#define SOC_ADC_H_
/*---------------------------------------------------------------------------*/
/** \name ADC and RNG Register offset declarations
* @{
*/
#define SOC_ADC_ADCCON1 0x400D7000 /**< ADC Control 1 */
#define SOC_ADC_ADCCON2 0x400D7004 /**< ADC Control 2 */
#define SOC_ADC_ADCCON3 0x400D7008 /**< ADC Control 3 */
#define SOC_ADC_ADCL 0x400D700C /**< ADC Result, least significant part */
#define SOC_ADC_ADCH 0x400D7010 /**< ADC Result, most significant part */
#define SOC_ADC_RNDL 0x400D7014 /**< RNG low byte */
#define SOC_ADC_RNDH 0x400D7018 /**< RNG high byte */
#define SOC_ADC_CMPCTL 0x400D7024 /**< Analog comparator control and status */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SOC_ADC_ADCCON1 register bit masks
* @{
*/
#define SOC_ADC_ADCCON1_EOC 0x00000080 /**< End of conversion */
#define SOC_ADC_ADCCON1_ST 0x00000040 /**< Start conversion */
#define SOC_ADC_ADCCON1_STSEL 0x00000030 /**< Start select */
#define SOC_ADC_ADCCON1_RCTRL 0x0000000C /**< Controls the 16-bit RNG */
#define SOC_ADC_ADCCON1_RCTRL1 0x00000008 /**< RCTRL high bit */
#define SOC_ADC_ADCCON1_RCTRL0 0x00000004 /**< RCTRL low bit */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SOC_ADC_ADCCON2 register bit masks
* @{
*/
#define SOC_ADC_ADCCON2_SREF 0x000000C0 /**< Reference voltage for sequence */
#define SOC_ADC_ADCCON2_SDIV 0x00000030 /**< Decimation rate for sequence */
#define SOC_ADC_ADCCON2_SCH 0x0000000F /**< Sequence channel select */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SOC_ADC_ADCCON3 register bit masks
* @{
*/
#define SOC_ADC_ADCCON3_EREF 0x000000C0 /**< Reference voltage for extra */
#define SOC_ADC_ADCCON3_EDIV 0x00000030 /**< Decimation rate for extra */
#define SOC_ADC_ADCCON3_ECH 0x0000000F /**< Single channel select */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SOC_ADC_ADC[L:H] register bit masks
* @{
*/
#define SOC_ADC_ADCL_ADC 0x000000FC /**< ADC Result, least significant part */
#define SOC_ADC_ADCH_ADC 0x000000FF /**< ADC Result, most significant part */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SOC_ADC_RND[L:H] register bit masks
* @{
*/
#define SOC_ADC_RNDL_RNDL 0x000000FF /**< Random value/seed or CRC result low byte */
#define SOC_ADC_RNDH_RNDH 0x000000FF /**< Random value or CRC result/input data, high byte */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SOC_ADC_CMPCTL register bit masks
* @{
*/
#define SOC_ADC_CMPCTL_EN 0x00000002 /**< Comparator enable */
#define SOC_ADC_CMPCTL_OUTPUT 0x00000001 /**< Comparator output */
/** @} */
#endif /* SOC_ADC_H_ */
/**
* @}
* @}
*/

75
cpu/cc2538/dev/sys-ctrl.c Normal file
View File

@ -0,0 +1,75 @@
/*
* 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 cc2538-sys-ctrl
* @{
*
* \file
* Implementation of the cc2538 System Control driver
*/
#include "reg.h"
#include "cpu.h"
#include "dev/sys-ctrl.h"
#include <stdint.h>
/*---------------------------------------------------------------------------*/
void
sys_ctrl_init()
{
uint32_t val;
/*
* Desired Clock Ctrl configuration:
* 32KHz source: RC
* System Clock: 32 MHz
* Power Down Unused
* I/O Div: 16MHz
* Sys Div: 16MHz
* Rest: Don't care
*/
val = SYS_CTRL_CLOCK_CTRL_OSC32K | SYS_CTRL_CLOCK_CTRL_OSC_PD
| SYS_CTRL_CLOCK_CTRL_IO_DIV_16MHZ | SYS_CTRL_CLOCK_CTRL_SYS_DIV_16MHZ;
REG(SYS_CTRL_CLOCK_CTRL) = val;
while((REG(SYS_CTRL_CLOCK_STA) & SYS_CTRL_CLOCK_STA_OSC) != 0);
}
/*---------------------------------------------------------------------------*/
void
sys_ctrl_reset()
{
REG(SYS_CTRL_PWRDBG) = SYS_CTRL_PWRDBG_FORCE_WARM_RESET;
}
/**
* @}
* @}
*/

248
cpu/cc2538/dev/sys-ctrl.h Normal file
View File

@ -0,0 +1,248 @@
/*
* 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 cc2538
* @{
*
* \defgroup cc2538-sys-ctrl cc2538 System Control
*
* Driver for the cc2538 System Control Module
* @{
*
* \file
* Header file for the cc2538 System Control driver
*/
#ifndef SYS_CTRL_H_
#define SYS_CTRL_H_
/*---------------------------------------------------------------------------*/
/** \name SysCtrl Constants, used by the SYS_DIV and IO_DIV bits of the
* SYS_CTRL_CLOCK_CTRL register
* @{
*/
#define SYS_CTRL_32MHZ 32000000
#define SYS_CTRL_16MHZ 16000000
#define SYS_CTRL_8MHZ 8000000
#define SYS_CTRL_4MHZ 4000000
#define SYS_CTRL_2MHZ 2000000
#define SYS_CTRL_1MHZ 1000000
#define SYS_CTRL_500KHZ 500000
#define SYS_CTRL_250KHZ 250000
/** @} */
/*---------------------------------------------------------------------------*/
/** \name Definitions of Sys Ctrl registers
* @{
*/
#define SYS_CTRL_CLOCK_CTRL 0x400D2000 /**< Clock control register */
#define SYS_CTRL_CLOCK_STA 0x400D2004 /**< Clock status register */
#define SYS_CTRL_RCGCGPT 0x400D2008 /**< GPT[3:0] clocks - active mode */
#define SYS_CTRL_SCGCGPT 0x400D200C /**< GPT[3:0] clocks - sleep mode */
#define SYS_CTRL_DCGCGPT 0x400D2010 /**< GPT[3:0] clocks - PM0 */
#define SYS_CTRL_SRGPT 0x400D2014 /**< GPT[3:0] reset control */
#define SYS_CTRL_RCGCSSI 0x400D2018 /**< SSI[1:0] clocks - active mode */
#define SYS_CTRL_SCGCSSI 0x400D201C /**< SSI[1:0] clocks - sleep mode */
#define SYS_CTRL_DCGCSSI 0x400D2020 /**< SSI[1:0] clocks - PM0 mode */
#define SYS_CTRL_SRSSI 0x400D2024 /**< SSI[1:0] reset control */
#define SYS_CTRL_RCGCUART 0x400D2028 /**< UART[1:0] clocks - active mode */
#define SYS_CTRL_SCGCUART 0x400D202C /**< UART[1:0] clocks - sleep mode */
#define SYS_CTRL_DCGCUART 0x400D2030 /**< UART[1:0] clocks - PM0 */
#define SYS_CTRL_SRUART 0x400D2034 /**< UART[1:0] reset control */
#define SYS_CTRL_RCGCI2C 0x400D2038 /**< I2C clocks - active mode */
#define SYS_CTRL_SCGCI2C 0x400D203C /**< I2C clocks - sleep mode */
#define SYS_CTRL_DCGCI2C 0x400D2040 /**< I2C clocks - PM0 */
#define SYS_CTRL_SRI2C 0x400D2044 /**< I2C clocks - reset control */
#define SYS_CTRL_RCGCSEC 0x400D2048 /**< Sec Mod clocks - active mode */
#define SYS_CTRL_SCGCSEC 0x400D204C /**< Sec Mod clocks - sleep mode */
#define SYS_CTRL_DCGCSEC 0x400D2050 /**< Sec Mod clocks - PM0 */
#define SYS_CTRL_SRSEC 0x400D2054 /**< Sec Mod reset control */
#define SYS_CTRL_PMCTL 0x400D2058 /**< Power Mode Control */
#define SYS_CTRL_SRCRC 0x400D205C /**< CRC on state retention */
#define SYS_CTRL_PWRDBG 0x400D2074 /**< Power debug register */
#define SYS_CTRL_CLD 0x400D2080 /**< clock loss detection feature */
#define SYS_CTRL_IWE 0x400D2094 /**< interrupt wake-up. */
#define SYS_CTRL_I_MAP 0x400D2098 /**< Interrupt map select */
#define SYS_CTRL_RCGCRFC 0x400D20A8 /**< RF Core clocks - active mode */
#define SYS_CTRL_SCGCRFC 0x400D20AC /**< RF Core clocks - Sleep mode */
#define SYS_CTRL_DCGCRFC 0x400D20B0 /**< RF Core clocks - PM0 */
#define SYS_CTRL_EMUOVR 0x400D20B4 /**< Emulator override */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SYS_CTRL_CLOCK_CTRL register bit masks
* @{
*/
#define SYS_CTRL_CLOCK_CTRL_OSC32K_CALDIS 0x02000000
#define SYS_CTRL_CLOCK_CTRL_OSC32K 0x01000000
#define SYS_CTRL_CLOCK_CTRL_AMP_DET 0x00200000
#define SYS_CTRL_CLOCK_CTRL_OSC_PD 0x00020000
#define SYS_CTRL_CLOCK_CTRL_OSC 0x00010000
#define SYS_CTRL_CLOCK_CTRL_IO_DIV 0x00000700
#define SYS_CTRL_CLOCK_CTRL_SYS_DIV 0x00000007
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SYS_CTRL_CLOCK_STA register bit masks
* @{
*/
#define SYS_CTRL_CLOCK_STA_SYNC_32K 0x04000000
#define SYS_CTRL_CLOCK_STA_OSC32K_CALDIS 0x02000000
#define SYS_CTRL_CLOCK_STA_OSC32K 0x01000000
#define SYS_CTRL_CLOCK_STA_RST 0x00C00000
#define SYS_CTRL_CLOCK_STA_SOURCE_CHANGE 0x00100000
#define SYS_CTRL_CLOCK_STA_XOSC_STB 0x00080000
#define SYS_CTRL_CLOCK_STA_HSOSC_STB 0x00040000
#define SYS_CTRL_CLOCK_STA_OSC_PD 0x00020000
#define SYS_CTRL_CLOCK_STA_OSC 0x00010000
#define SYS_CTRL_CLOCK_STA_IO_DIV 0x00000700
#define SYS_CTRL_CLOCK_STA_RTCLK_FREQ 0x00000018
#define SYS_CTRL_CLOCK_STA_SYS_DIV 0x00000007
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SYS_CTRL_RCGCGPT register bit masks
* @{
*/
#define SYS_CTRL_RCGCGPT_GPT3 0x00000008 /**< GPT3 clock enable, CPU running */
#define SYS_CTRL_RCGCGPT_GPT2 0x00000004 /**< GPT2 clock enable, CPU running */
#define SYS_CTRL_RCGCGPT_GPT1 0x00000002 /**< GPT1 clock enable, CPU running */
#define SYS_CTRL_RCGCGPT_GPT0 0x00000001 /**< GPT0 clock enable, CPU running */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SYS_CTRL_SCGCGPT register bit masks
* @{
*/
#define SYS_CTRL_SCGCGPT_GPT3 0x00000008 /**< GPT3 clock enable, CPU IDLE */
#define SYS_CTRL_SCGCGPT_GPT2 0x00000004 /**< GPT2 clock enable, CPU IDLE */
#define SYS_CTRL_SCGCGPT_GPT1 0x00000002 /**< GPT1 clock enable, CPU IDLE */
#define SYS_CTRL_SCGCGPT_GPT0 0x00000001 /**< GPT0 clock enable, CPU IDLE */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SYS_CTRL_DCGCGPT register bit masks
* @{
*/
#define SYS_CTRL_DCGCGPT_GPT3 0x00000008 /**< GPT3 clock enable, PM0 */
#define SYS_CTRL_DCGCGPT_GPT2 0x00000004 /**< GPT2 clock enable, PM0 */
#define SYS_CTRL_DCGCGPT_GPT1 0x00000002 /**< GPT1 clock enable, PM0 */
#define SYS_CTRL_DCGCGPT_GPT0 0x00000001 /**< GPT0 clock enable, PM0 */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SYS_CTRL_SRGPT register bits
* @{
*/
#define SYS_CTRL_SRGPT_GPT3 0x00000008 /**< GPT3 is reset */
#define SYS_CTRL_SRGPT_GPT2 0x00000004 /**< GPT2 is reset */
#define SYS_CTRL_SRGPT_GPT1 0x00000002 /**< GPT1 is reset */
#define SYS_CTRL_SRGPT_GPT0 0x00000001 /**< GPT0 is reset */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SYS_CTRL_PWRDBG register bits
* @{
*/
#define SYS_CTRL_PWRDBG_FORCE_WARM_RESET 0x00000008
/** @} */
/*---------------------------------------------------------------------------*/
/** \name Possible values for the SYS_CTRL_CLOCK_CTRL_SYS_DIV bits
* @{
*/
#define SYS_CTRL_CLOCK_CTRL_SYS_DIV_32MHZ 0x00000000
#define SYS_CTRL_CLOCK_CTRL_SYS_DIV_16MHZ 0x00000001
#define SYS_CTRL_CLOCK_CTRL_SYS_DIV_8MHZ 0x00000002
#define SYS_CTRL_CLOCK_CTRL_SYS_DIV_4MHZ 0x00000003
#define SYS_CTRL_CLOCK_CTRL_SYS_DIV_2MHZ 0x00000004
#define SYS_CTRL_CLOCK_CTRL_SYS_DIV_1MHZ 0x00000005
#define SYS_CTRL_CLOCK_CTRL_SYS_DIV_500KHZ 0x00000006
#define SYS_CTRL_CLOCK_CTRL_SYS_DIV_250KHZ 0x00000007
/** @} */
/*---------------------------------------------------------------------------*/
/** \name Possible values for the SYS_CTRL_CLOCK_CTRL_IO_DIV bits
* @{
*/
#define SYS_CTRL_CLOCK_CTRL_IO_DIV_32MHZ 0x00000000
#define SYS_CTRL_CLOCK_CTRL_IO_DIV_16MHZ 0x00000100
#define SYS_CTRL_CLOCK_CTRL_IO_DIV_8MHZ 0x00000200
#define SYS_CTRL_CLOCK_CTRL_IO_DIV_4MHZ 0x00000300
#define SYS_CTRL_CLOCK_CTRL_IO_DIV_2MHZ 0x00000400
#define SYS_CTRL_CLOCK_CTRL_IO_DIV_1MHZ 0x00000500
#define SYS_CTRL_CLOCK_CTRL_IO_DIV_500KHZ 0x00000600
#define SYS_CTRL_CLOCK_CTRL_IO_DIV_250KHZ 0x00000700
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SYS_CTRL_RCGCUART Register Bit-Masks
* @{
*/
#define SYS_CTRL_RCGCUART_UART1 0x00000002 /**< UART1 Clock, CPU running */
#define SYS_CTRL_RCGCUART_UART0 0x00000001 /**< UART0 Clock, CPU running */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SYS_CTRL_SCGCUART Register Bit-Masks
* @{
*/
#define SYS_CTRL_SCGCUART_UART1 0x00000002 /**< UART1 Clock, CPU IDLE */
#define SYS_CTRL_SCGCUART_UART0 0x00000001 /**< UART0 Clock, CPU IDLE */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SYS_CTRL_RCGCUART Register Bit-Masks
* @{
*/
#define SYS_CTRL_DCGCUART_UART1 0x00000002 /**< UART1 Clock, PM0 */
#define SYS_CTRL_DCGCUART_UART0 0x00000001 /**< UART0 Clock, PM0 */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SYS_CTRL_SRUART register bits
* @{
*/
#define SYS_CTRL_SRUART_UART1 0x00000002 /**< UART1 module is reset */
#define SYS_CTRL_SRUART_UART0 0x00000001 /**< UART0 module is reset */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SYS_CTRL_PMCTL register values
* @{
*/
#define SYS_CTRL_PMCTL_PM3 0x00000003 /**< PM3 */
#define SYS_CTRL_PMCTL_PM2 0x00000002 /**< PM2 */
#define SYS_CTRL_PMCTL_PM1 0x00000001 /**< PM1 */
#define SYS_CTRL_PMCTL_PM0 0x00000000 /**< PM0 */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SysCtrl functions
* @{
*/
/** \brief Initialises the System Control Driver. The main purpose of this
* function is to power up and select clocks and oscillators */
void sys_ctrl_init();
/** \brief Generates a warm reset through the SYS_CTRL_PWRDBG register */
void sys_ctrl_reset();
/** @} */
#endif /* SYS_CTRL_H_ */
/**
* @}
* @}
*/

53
cpu/cc2538/dev/systick.h Normal file
View File

@ -0,0 +1,53 @@
/*
* 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.
*/
/**
* \file
* Header for with definitions related to the cc2538 SysTick
*/
/*---------------------------------------------------------------------------*/
#ifndef SYSTICK_H_
#define SYSTICK_H_
/*---------------------------------------------------------------------------*/
/* SysTick Register Definitions */
#define SYSTICK_STCTRL 0xE000E010 /* Control and Status */
#define SYSTICK_STRELOAD 0xE000E014 /* Reload Value */
#define SYSTICK_STCURRENT 0xE000E018 /* Current Value */
#define SYSTICK_STCAL 0xE000E01C /* SysTick Calibration */
/*---------------------------------------------------------------------------*/
/* Bit Definitions for the STCTRL Register */
#define SYSTICK_STCTRL_COUNT 0x00010000 /* Count Flag */
#define SYSTICK_STCTRL_CLK_SRC 0x00000004 /* Clock Source */
#define SYSTICK_STCTRL_INTEN 0x00000002 /* Interrupt Enable */
#define SYSTICK_STCTRL_ENABLE 0x00000001 /* Enable */
#endif /* SYSTICK_H_ */
/** @} */

172
cpu/cc2538/dev/uart.c Normal file
View File

@ -0,0 +1,172 @@
/*
* 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 cc2538-uart
* @{
*
* \file
* Implementation of the cc2538 UART driver
*/
#include "contiki.h"
#include "sys/energest.h"
#include "dev/sys-ctrl.h"
#include "dev/ioc.h"
#include "dev/gpio.h"
#include "dev/uart.h"
#include "reg.h"
#include <stdint.h>
#include <string.h>
static int (* input_handler)(unsigned char c);
/*---------------------------------------------------------------------------*/
static void
reset(void)
{
uint32_t lchr;
/* Make sure the UART is disabled before trying to configure it */
REG(UART_0_BASE | UART_CTL) = UART_CTL_TXE | UART_CTL_RXE;
/* Clear error status */
REG(UART_0_BASE | UART_ECR) = 0xFF;
/* Store LCHR configuration */
lchr = REG(UART_0_BASE | UART_LCRH);
/* Flush FIFOs by clearing LCHR.FEN */
REG(UART_0_BASE | UART_LCRH) = 0;
/* Restore LCHR configuration */
REG(UART_0_BASE | UART_LCRH) = lchr;
/* UART Enable */
REG(UART_0_BASE | UART_CTL) |= UART_CTL_UARTEN;
}
/*---------------------------------------------------------------------------*/
void
uart_init(void)
{
/* Enable clock for the UART while Running, in Sleep and Deep Sleep */
REG(SYS_CTRL_RCGCUART) |= SYS_CTRL_RCGCUART_UART0;
REG(SYS_CTRL_SCGCUART) |= SYS_CTRL_DCGCUART_UART0;
REG(SYS_CTRL_DCGCUART) |= SYS_CTRL_DCGCUART_UART0;
/* Run on SYS_DIV */
REG(UART_0_BASE | UART_CC) = 0;
/* PA1: UART TX */
REG(IOC_PA1_SEL) = IOC_PXX_SEL_UART0_TXD;
/* PA0: UART RX */
REG(IOC_UARTRXD_UART0) = IOC_INPUT_SEL_PA0;
/* Pad Control: PA1 Output Enable */
REG(IOC_PA1_OVER) = IOC_OVERRIDE_OE;
/* Set PA[1:0] to peripheral mode */
REG(GPIO_A_BASE | GPIO_AFSEL) |= (0x00000002 | 0x00000001);
/*
* UART Interrupt Masks:
* Acknowledge RX and RX Timeout
* Acknowledge Framing, Overrun and Break Errors
*/
REG(UART_0_BASE | UART_IM) = UART_IM_RXIM | UART_IM_RTIM;
REG(UART_0_BASE | UART_IM) |= UART_IM_OEIM | UART_IM_BEIM | UART_IM_FEIM;
REG(UART_0_BASE | UART_IFLS) =
UART_IFLS_RXIFLSEL_1_8 | UART_IFLS_TXIFLSEL_1_2;
/* Make sure the UART is disabled before trying to configure it */
REG(UART_0_BASE | UART_CTL) = UART_CTL_TXE | UART_CTL_RXE;
/* Baud Rate Generation */
REG(UART_0_BASE | UART_IBRD) = UART_CONF_IBRD;
REG(UART_0_BASE | UART_FBRD) = UART_CONF_FBRD;
/* UART Control: 8N1 with FIFOs */
REG(UART_0_BASE | UART_LCRH) = UART_LCRH_WLEN_8 | UART_LCRH_FEN;
/* UART Enable */
REG(UART_0_BASE | UART_CTL) |= UART_CTL_UARTEN;
/* Enable UART0 Interrupts */
nvic_interrupt_enable(NVIC_INT_UART0);
}
/*---------------------------------------------------------------------------*/
void
uart_set_input(int (* input)(unsigned char c))
{
input_handler = input;
}
/*---------------------------------------------------------------------------*/
void
uart_write_byte(uint8_t b)
{
/* Block if the TX FIFO is full */
while(REG(UART_0_BASE | UART_FR) & UART_FR_TXFF);
REG(UART_0_BASE | UART_DR) = b;
}
/*---------------------------------------------------------------------------*/
void
uart_isr(void)
{
uint16_t mis;
ENERGEST_ON(ENERGEST_TYPE_IRQ);
/* Store the current MIS and clear all flags early, except the RTM flag.
* This will clear itself when we read out the entire FIFO contents */
mis = REG(UART_0_BASE | UART_MIS) & 0x0000FFFF;
REG(UART_0_BASE | UART_ICR) = 0x0000FFBF;
if(mis & (UART_MIS_RXMIS | UART_MIS_RTMIS)) {
while(!(REG(UART_0_BASE | UART_FR) & UART_FR_RXFE)) {
if(input_handler != NULL) {
input_handler((unsigned char)(REG(UART_0_BASE | UART_DR) & 0xFF));
} else {
/* To prevent an Overrun Error, we need to flush the FIFO even if we
* don't have an input_handler. Use mis as a data trash can */
mis = REG(UART_0_BASE | UART_DR);
}
}
} else if(mis & (UART_MIS_OEMIS | UART_MIS_BEMIS | UART_MIS_FEMIS)) {
/* ISR triggered due to some error condition */
reset();
}
ENERGEST_OFF(ENERGEST_TYPE_IRQ);
}
/** @} */

382
cpu/cc2538/dev/uart.h Normal file
View File

@ -0,0 +1,382 @@
/*
* 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 cc2538
* @{
*
* \defgroup cc2538-uart cc2538 UART
*
* Driver for the cc2538 UART controller
* @{
*
* \file
* Header file for the cc2538 UART driver
*/
#ifndef UART_H_
#define UART_H_
#include "contiki.h"
#include <stdint.h>
/*---------------------------------------------------------------------------*/
/** \name UART base addresses
* @{
*/
#define UART_0_BASE 0x4000C000
#define UART_1_BASE 0x4000D000
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name Baud rate defines
*
* Used in uart_init() to set the values of UART_IBRD and UART_FBRD in order to
* achieve some standard baud rates. These defines assume that the UART is
* clocked at 16MHz and that Clock Div is 16 (UART_CTL:HSE clear)
* @{
*/
#define UART_IBRD_115200 8 /**< IBRD value for baud rate 115200 */
#define UART_FBRD_115200 44 /**< FBRD value for baud rate 115200 */
#define UART_IBRD_230400 4 /**< IBRD value for baud rate 230400 */
#define UART_FBRD_230400 22 /**< FBRD value for baud rate 230400 */
#define UART_IBRD_460800 2 /**< IBRD value for baud rate 230400 */
#define UART_FBRD_460800 11 /**< FBRD value for baud rate 230400 */
#if UART_CONF_BAUD_RATE==115200
#define UART_CONF_IBRD UART_IBRD_115200
#define UART_CONF_FBRD UART_FBRD_115200
#elif UART_CONF_BAUD_RATE==230400
#define UART_CONF_IBRD UART_IBRD_230400
#define UART_CONF_FBRD UART_FBRD_230400
#elif UART_CONF_BAUD_RATE==460800
#define UART_CONF_IBRD UART_IBRD_460800
#define UART_CONF_FBRD UART_FBRD_460800
#else /* Bail out with an error unless the user provided custom values */
#if !(defined UART_CONF_IBRD && defined UART_CONF_FBRD)
#error "UART baud rate misconfigured and custom IBRD/FBRD values not provided"
#error "Check the value of UART_CONF_BAUD_RATE in contiki-conf.h or project-conf.h"
#error "Supported values are 115200, 230400 and 460800. Alternatively, you can"
#error "provide custom values for UART_CONF_IBRD and UART_CONF_FBRD"
#endif
#endif
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART Register Offsets
* @{
*/
#define UART_DR 0x00000000 /**< UART data */
#define UART_RSR 0x00000004 /**< UART RX status and err clear */
#define UART_ECR 0x00000004 /**< UART RX status and err clear */
#define UART_FR 0x00000018 /**< UART flag */
#define UART_ILPR 0x00000020 /**< UART IrDA low-power */
#define UART_IBRD 0x00000024 /**< UART BAUD divisor: integer */
#define UART_FBRD 0x00000028 /**< UART BAUD divisor: fractional */
#define UART_LCRH 0x0000002C /**< UART line control */
#define UART_CTL 0x00000030 /**< UART control */
#define UART_IFLS 0x00000034 /**< UART interrupt FIFO level */
#define UART_IM 0x00000038 /**< UART interrupt mask */
#define UART_RIS 0x0000003C /**< UART raw interrupt status */
#define UART_MIS 0x00000040 /**< UART masked interrupt status */
#define UART_ICR 0x00000044 /**< UART interrupt clear */
#define UART_DMACTL 0x00000048 /**< UART DMA control */
#define UART_LCTL 0x00000090 /**< UART LIN control */
#define UART_LSS 0x00000094 /**< UART LIN snap shot */
#define UART_LTIM 0x00000098 /**< UART LIN timer */
#define UART_NINEBITADDR 0x000000A4 /**< UART 9-bit self address */
#define UART_NINEBITAMASK 0x000000A8 /**< UART 9-bit self address mask */
#define UART_PP 0x00000FC0 /**< UART peripheral properties */
#define UART_CC 0x00000FC8 /**< UART clock configuration */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_DR Register Bit-Masks
* @{
*/
#define UART_DR_OE 0x00000800 /**< UART overrun error */
#define UART_DR_BE 0x00000400 /**< UART break error */
#define UART_DR_PE 0x00000200 /**< UART parity error */
#define UART_DR_FE 0x00000100 /**< UART framing error */
#define UART_DR_DATA 0x000000FF /**< Data transmitted or received */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_RSR Register Bit-Masks
* @{
*/
#define UART_RSR_OE 0x00000008 /**< UART overrun error */
#define UART_RSR_BE 0x00000004 /**< UART break error */
#define UART_RSR_PE 0x00000002 /**< UART parity error */
#define UART_RSR_FE 0x00000001 /**< UART framing error */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_ECR Register Bit-Masks
* @{
*/
#define UART_ECR_DATA 0x000000FF /**< Error clear */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_FR Register Bit-Masks
* @{
*/
#define UART_FR_TXFE 0x00000080 /**< UART transmit FIFO empty */
#define UART_FR_RXFF 0x00000040 /**< UART receive FIFO full */
#define UART_FR_TXFF 0x00000020 /**< UART transmit FIFO full */
#define UART_FR_RXFE 0x00000010 /**< UART receive FIFO empty */
#define UART_FR_BUSY 0x00000008 /**< UART busy */
#define UART_FR_CTS 0x00000001 /**< Clear to send */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_ILPR Register Bit-Masks
* @{
*/
#define UART_ILPR_ILPDVSR 0x000000FF /**< IrDA low-power divisor */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_IBRD Register Bit-Masks
* @{
*/
#define UART_IBRD_DIVINT 0x0000FFFF /**< Integer baud-rate divisor */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_FPRD Register Bit-Masks
* @{
*/
#define UART_FBRD_DIVFRAC 0x0000003F /**< Fractional baud-rate divisor */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_LCRH Register Bit-Masks
* @{
*/
#define UART_LCRH_SPS 0x00000080 /**< UART stick parity select */
#define UART_LCRH_WLEN 0x00000060 /**< UART word length */
#define UART_LCRH_FEN 0x00000010 /**< UART enable FIFOs */
#define UART_LCRH_STP2 0x00000008 /**< UART two stop bits select */
#define UART_LCRH_EPS 0x00000004 /**< UART even parity select */
#define UART_LCRH_PEN 0x00000002 /**< UART parity enable */
#define UART_LCRH_BRK 0x00000001 /**< UART send break */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_LCRH_WLEN Values
* @{
*/
#define UART_LCRH_WLEN_8 0x00000060
#define UART_LCRH_WLEN_7 0x00000040
#define UART_LCRH_WLEN_6 0x00000020
#define UART_LCRH_WLEN_5 0x00000000
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_CTL Register Bit-Masks
* @{
*/
#define UART_CTL_RXE 0x00000200 /**< UART receive enable */
#define UART_CTL_TXE 0x00000100 /**< UART transmit enable */
#define UART_CTL_LBE 0x00000080 /**< UART loop back enable */
#define UART_CTL_LIN 0x00000040 /**< LIN mode enable */
#define UART_CTL_HSE 0x00000020 /**< High-speed enable */
#define UART_CTL_EOT 0x00000010 /**< End of transmission */
#define UART_CTL_SMART 0x00000008 /**< ISO 7816 Smart Card support */
#define UART_CTL_SIRLP 0x00000004 /**< UART SIR low-power mode */
#define UART_CTL_SIREN 0x00000002 /**< UART SIR enable */
#define UART_CTL_UARTEN 0x00000001 /**< UART enable */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_IFLS Register Bit-Masks
* @{
*/
#define UART_IFLS_RXIFLSEL 0x00000038 /**< UART RX FIFO level select */
#define UART_IFLS_TXIFLSEL 0x00000007 /**< UART TX FIFO level select */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_IFLS_RXIFLSEL Possible Values
* @{
*/
#define UART_IFLS_RXIFLSEL_7_8 0x00000020 /**< UART RX FIFO >= 7/8 full */
#define UART_IFLS_RXIFLSEL_3_4 0x00000018 /**< UART RX FIFO >= 3/4 full */
#define UART_IFLS_RXIFLSEL_1_2 0x00000010 /**< UART RX FIFO >= 1/2 full */
#define UART_IFLS_RXIFLSEL_1_4 0x00000008 /**< UART RX FIFO >= 1/4 full */
#define UART_IFLS_RXIFLSEL_1_8 0x00000000 /**< UART RX FIFO >= 1/8 full */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_IFLS_TXIFLSEL Possible Values
* @{
*/
#define UART_IFLS_TXIFLSEL_1_8 0x00000004 /**< UART TX FIFO >= 1/8 empty */
#define UART_IFLS_TXIFLSEL_1_4 0x00000003 /**< UART TX FIFO >= 1/4 empty */
#define UART_IFLS_TXIFLSEL_1_2 0x00000002 /**< UART TX FIFO >= 1/2 empty */
#define UART_IFLS_TXIFLSEL_3_4 0x00000001 /**< UART TX FIFO >= 3/4 empty */
#define UART_IFLS_TXIFLSEL_7_8 0x00000000 /**< UART TX FIFO >= 7/8 empty */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_IM Register Bit-Masks
* @{
*/
#define UART_IM_LME5IM 0x00008000 /**< LIN mode edge 5 intr mask */
#define UART_IM_LME1IM 0x00004000 /**< LIN mode edge 1 intr mask */
#define UART_IM_LMSBIM 0x00002000 /**< LIN mode sync break mask */
#define UART_IM_NINEBITIM 0x00001000 /**< 9-bit mode interrupt mask */
#define UART_IM_OEIM 0x00000400 /**< UART overrun error mask */
#define UART_IM_BEIM 0x00000200 /**< UART break error mask */
#define UART_IM_PEIM 0x00000100 /**< UART parity error mask */
#define UART_IM_FEIM 0x00000080 /**< UART framing error */
#define UART_IM_RTIM 0x00000040 /**< UART receive time-out mask */
#define UART_IM_TXIM 0x00000020 /**< UART transmit intr mask */
#define UART_IM_RXIM 0x00000010 /**< UART receive interrupt mask */
#define UART_IM_CTSIM 0x00000002 /**< UART CTS modem mask */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_RIS Register Bit-Masks
* @{
*/
#define UART_RIS_LME5RIS 0x00008000 /**< LIN mode edge 5 raw */
#define UART_RIS_LME1RIS 0x00004000 /**< LIN mode edge 1 raw */
#define UART_RIS_LMSBRIS 0x00002000 /**< LIN mode sync break raw */
#define UART_RIS_NINEBITRIS 0x00001000 /**< 9-bit mode raw intr */
#define UART_RIS_OERIS 0x00000400 /**< UART overrun error raw */
#define UART_RIS_BERIS 0x00000200 /**< UART break error raw */
#define UART_RIS_PERIS 0x00000100 /**< UART parity error raw */
#define UART_RIS_FERIS 0x00000080 /**< UART framing error raw */
#define UART_RIS_RTRIS 0x00000040 /**< UART RX time-out raw */
#define UART_RIS_TXRIS 0x00000020 /**< UART transmit raw */
#define UART_RIS_RXRIS 0x00000010 /**< UART receive raw */
#define UART_RIS_CTSRIS 0x00000002 /**< UART CTS modem */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_RIS Register Bit-Masks
* @{
*/
#define UART_MIS_LME5MIS 0x00008000 /**< LIN mode edge 5 masked stat */
#define UART_MIS_LME1MIS 0x00004000 /**< LIN mode edge 1 masked stat */
#define UART_MIS_LMSBMIS 0x00002000 /**< LIN mode sync br masked stat */
#define UART_MIS_NINEBITMIS 0x00001000 /**< 9-bit mode masked stat */
#define UART_MIS_OEMIS 0x00000400 /**< UART overrun err masked stat */
#define UART_MIS_BEMIS 0x00000200 /**< UART break err masked stat */
#define UART_MIS_PEMIS 0x00000100 /**< UART parity err masked stat */
#define UART_MIS_FEMIS 0x00000080 /**< UART framing err masked stat */
#define UART_MIS_RTMIS 0x00000040 /**< UART RX time-out masked stat */
#define UART_MIS_TXMIS 0x00000020 /**< UART TX masked intr stat */
#define UART_MIS_RXMIS 0x00000010 /**< UART RX masked intr stat */
#define UART_MIS_CTSMIS 0x00000002 /**< UART CTS modem masked stat */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_ICR Register Bit-Masks
* @{
*/
#define UART_ICR_LME5IC 0x00008000 /**< LIN mode edge 5 intr clear */
#define UART_ICR_LME1IC 0x00004000 /**< LIN mode edge 1 intr clear */
#define UART_ICR_LMSBIC 0x00002000 /**< LIN mode sync br intr clear */
#define UART_ICR_NINEBITIC 0x00001000 /**< 9-bit mode intr clear */
#define UART_ICR_OEIC 0x00000400 /**< Overrun error intr clear */
#define UART_ICR_BEIC 0x00000200 /**< Break error intr clear */
#define UART_ICR_PEIC 0x00000100 /**< Parity error intr clear */
#define UART_ICR_FEIC 0x00000080 /**< Framing error intr clear */
#define UART_ICR_RTIC 0x00000040 /**< Receive time-out intr clear */
#define UART_ICR_TXIC 0x00000020 /**< Transmit intr clear */
#define UART_ICR_RXIC 0x00000010 /**< Receive intr clear */
#define UART_ICR_CTSIC 0x00000002 /**< UART CTS modem intr clear */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_DMACTL Register Bit-Masks
* @{
*/
#define UART_DMACTL_DMAERR 0x00000004 /**< DMA on error */
#define UART_DMACTL_TXDMAE 0x00000002 /**< Transmit DMA enable */
#define UART_DMACTL_RXDMAE 0x00000001 /**< Receive DMA enable */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_LCTL Register Bit-Masks
* @{
*/
#define UART_LCTL_BLEN 0x00000030 /**< Sync break length */
#define UART_LCTL_MASTER 0x00000001 /**< LIN master enable */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_LSS Register Bit-Masks
* @{
*/
#define UART_LSS_TSS 0x0000FFFF /**< Timer snap shot */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_LTIM Register Bit-Masks
* @{
*/
#define UART_LTIM_TIMER 0x0000FFFF /**< Timer value */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_O_NINEBITADDR Register Bit-Masks
* @{
*/
#define UART_NINEBITADDR_NINEBITEN 0x00008000 /**< Enable 9-bit mode */
#define UART_NINEBITADDR_ADDR 0x000000FF /**< Self address for 9-bit mode */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_O_NINEBITADDR Register Bit-Masks
* @{
*/
#define UART_NINEBITAMASK_RANGE 0x0000FF00 /**< Self addr range, 9-bit mode */
#define UART_NINEBITAMASK_MASK 0x000000FF /**< Self addr mask, 9-bit mode */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_PP Register Bit-Masks
* @{
*/
#define UART_PP_NB 0x00000002 /**< 9-bit support */
#define UART_PP_SC 0x00000001 /**< Smart card support */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART_CC Register Bit-Masks
* @{
*/
#define UART_CC_CS 0x00000007 /**< UART BAUD & sys clock source */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UART functions
* @{
*/
/** \brief Initialises the UART controller, configures I/O control
* and interrupts */
void uart_init(void);
/** \brief Sends a single character down the UART
* \param b The character to transmit
*/
void 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 uart_set_input(int (* input)(unsigned char c));
/** @} */
#endif /* UART_H_ */
/**
* @}
* @}
*/

51
cpu/cc2538/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 cc2538-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/uart.h"
#define BAUD2UBR(x) x
#define uart1_set_input(f) uart_set_input(f)
#endif /* UART1_H_ */
/** @} */

259
cpu/cc2538/dev/udma.c Normal file
View File

@ -0,0 +1,259 @@
/*
* Copyright (c) 2013, 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 cc2538-udma
* @{
*
* \file
* Implementation of the cc2538 micro-DMA driver
*/
#include "contiki-conf.h"
#include "dev/udma.h"
#include "dev/nvic.h"
#include "reg.h"
#include <stdint.h>
#include <string.h>
/*---------------------------------------------------------------------------*/
struct channel_ctrl {
uint32_t src_end_ptr;
uint32_t dst_end_ptr;
uint32_t ctrl_word;
uint32_t unused;
};
static volatile struct channel_ctrl channel_config[UDMA_CONF_MAX_CHANNEL + 1]
__attribute__ ((aligned(1024)));
/*---------------------------------------------------------------------------*/
void
udma_init()
{
memset(&channel_config, 0, sizeof(channel_config));
REG(UDMA_CFG) = UDMA_CFG_MASTEN;
REG(UDMA_CTLBASE) = (uint32_t)(&channel_config);
nvic_interrupt_enable(NVIC_INT_UDMA);
nvic_interrupt_enable(NVIC_INT_UDMA_ERR);
}
/*---------------------------------------------------------------------------*/
void
udma_set_channel_src(uint8_t channel, uint32_t src_end)
{
if(channel > UDMA_CONF_MAX_CHANNEL) {
return;
}
channel_config[channel].src_end_ptr = src_end;
}
/*---------------------------------------------------------------------------*/
void
udma_set_channel_dst(uint8_t channel, uint32_t dst_end)
{
if(channel > UDMA_CONF_MAX_CHANNEL) {
return;
}
channel_config[channel].dst_end_ptr = dst_end;
}
/*---------------------------------------------------------------------------*/
void
udma_set_channel_control_word(uint8_t channel, uint32_t ctrl)
{
if(channel > UDMA_CONF_MAX_CHANNEL) {
return;
}
channel_config[channel].ctrl_word = ctrl;
}
/*---------------------------------------------------------------------------*/
void
udma_set_channel_assignment(uint8_t channel, uint8_t enc)
{
uint32_t base_chmap = UDMA_CHMAP0;
uint8_t shift;
if(channel > UDMA_CONF_MAX_CHANNEL) {
return;
}
/* Calculate the address of the relevant CHMAP register */
base_chmap += (channel >> 3) * 4;
/* Calculate the shift value for the correct CHMAP register bits */
shift = (channel & 0x07);
/* Read CHMAPx value, zero out channel's bits and write the new value */
REG(base_chmap) = (REG(base_chmap) & ~(0x0F << shift)) | (enc << shift);
}
/*---------------------------------------------------------------------------*/
void
udma_channel_enable(uint8_t channel)
{
if(channel > UDMA_CONF_MAX_CHANNEL) {
return;
}
REG(UDMA_ENASET) |= 1 << channel;
}
/*---------------------------------------------------------------------------*/
void
udma_channel_disable(uint8_t channel)
{
if(channel > UDMA_CONF_MAX_CHANNEL) {
return;
}
/* Writes of 0 have no effect, this no need for RMW */
REG(UDMA_ENACLR) = 1 << channel;
}
/*---------------------------------------------------------------------------*/
void
udma_channel_use_alternate(uint8_t channel)
{
if(channel > UDMA_CONF_MAX_CHANNEL) {
return;
}
REG(UDMA_ALTSET) |= 1 << channel;
}
/*---------------------------------------------------------------------------*/
void
udma_channel_use_primary(uint8_t channel)
{
if(channel > UDMA_CONF_MAX_CHANNEL) {
return;
}
/* Writes of 0 have no effect, this no need for RMW */
REG(UDMA_ALTCLR) = 1 << channel;
}
/*---------------------------------------------------------------------------*/
void
udma_channel_prio_set_high(uint8_t channel)
{
if(channel > UDMA_CONF_MAX_CHANNEL) {
return;
}
REG(UDMA_PRIOSET) |= 1 << channel;
}
/*---------------------------------------------------------------------------*/
void
udma_channel_prio_set_default(uint8_t channel)
{
if(channel > UDMA_CONF_MAX_CHANNEL) {
return;
}
/* Writes of 0 have no effect, this no need for RMW */
REG(UDMA_PRIOCLR) = 1 << channel;
}
/*---------------------------------------------------------------------------*/
void
udma_channel_use_burst(uint8_t channel)
{
if(channel > UDMA_CONF_MAX_CHANNEL) {
return;
}
REG(UDMA_USEBURSTSET) |= 1 << channel;
}
/*---------------------------------------------------------------------------*/
void
udma_channel_use_single(uint8_t channel)
{
if(channel > UDMA_CONF_MAX_CHANNEL) {
return;
}
/* Writes of 0 have no effect, this no need for RMW */
REG(UDMA_USEBURSTCLR) = 1 << channel;
}
/*---------------------------------------------------------------------------*/
void
udma_channel_mask_set(uint8_t channel)
{
if(channel > UDMA_CONF_MAX_CHANNEL) {
return;
}
REG(UDMA_REQMASKSET) |= 1 << channel;
}
/*---------------------------------------------------------------------------*/
void
udma_channel_mask_clr(uint8_t channel)
{
if(channel > UDMA_CONF_MAX_CHANNEL) {
return;
}
/* Writes of 0 have no effect, this no need for RMW */
REG(UDMA_REQMASKCLR) = 1 << channel;
}
/*---------------------------------------------------------------------------*/
void
udma_channel_sw_request(uint8_t channel)
{
if(channel > UDMA_CONF_MAX_CHANNEL) {
return;
}
REG(UDMA_SWREQ) |= 1 << channel;
}
/*---------------------------------------------------------------------------*/
uint8_t
udma_channel_get_mode(uint8_t channel)
{
if(channel > UDMA_CONF_MAX_CHANNEL) {
return 0;
}
return (channel_config[channel].ctrl_word & 0x07);
}
/*---------------------------------------------------------------------------*/
void
udma_isr()
{
/* Simply clear Channel interrupt status for now */
REG(UDMA_CHIS) = UDMA_CHIS_CHIS;
}
/*---------------------------------------------------------------------------*/
void
udma_err_isr()
{
/* Stub Implementation, just clear the error flag */
REG(UDMA_ERRCLR) = 1;
}
/*---------------------------------------------------------------------------*/
/** @} */

703
cpu/cc2538/dev/udma.h Normal file
View File

@ -0,0 +1,703 @@
/*
* Copyright (c) 2013, 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 cc2538
* @{
*
* \defgroup cc2538-udma cc2538 micro-DMA
*
* Driver for the cc2538 uDMA controller
* @{
*
* \file
* Header file with register, macro and function declarations for the cc2538
* micro-DMA controller module
*/
#ifndef UDMA_H_
#define UDMA_H_
#include "contiki-conf.h"
/*
* Enable all uDMA channels unless a conf file tells us to do otherwise.
* Using all 31 channels will consume a lot of RAM for the channel control
* data structure. Thus it's wise to set this define to the number of the
* highest channel in use
*/
#ifndef UDMA_CONF_MAX_CHANNEL
#define UDMA_CONF_MAX_CHANNEL 31
#endif
/*---------------------------------------------------------------------------*/
/**
* \name uDMA Register offset declarations
* @{
*/
#define UDMA_STAT 0x400FF000 /**< DMA status */
#define UDMA_CFG 0x400FF004 /**< DMA configuration */
#define UDMA_CTLBASE 0x400FF008 /**< DMA channel control base pointer */
#define UDMA_ALTBASE 0x400FF00C /**< DMA alternate channel control base pointer */
#define UDMA_WAITSTAT 0x400FF010 /**< DMA channel wait-on-request status */
#define UDMA_SWREQ 0x400FF014 /**< DMA channel software request */
#define UDMA_USEBURSTSET 0x400FF018 /**< DMA channel useburst set */
#define UDMA_USEBURSTCLR 0x400FF01C /**< DMA channel useburst clear */
#define UDMA_REQMASKSET 0x400FF020 /**< DMA channel request mask set */
#define UDMA_REQMASKCLR 0x400FF024 /**< DMA channel request mask clear */
#define UDMA_ENASET 0x400FF028 /**< DMA channel enable set */
#define UDMA_ENACLR 0x400FF02C /**< DMA channel enable clear */
#define UDMA_ALTSET 0x400FF030 /**< DMA channel primary alternate set */
#define UDMA_ALTCLR 0x400FF034 /**< DMA channel primary alternate clear */
#define UDMA_PRIOSET 0x400FF038 /**< DMA channel priority set */
#define UDMA_PRIOCLR 0x400FF03C /**< DMA channel priority clear */
#define UDMA_ERRCLR 0x400FF04C /**< DMA bus error clear */
#define UDMA_CHASGN 0x400FF500 /**< DMA channel assignment */
#define UDMA_CHIS 0x400FF504 /**< DMA channel interrupt status */
#define UDMA_CHMAP0 0x400FF510 /**< DMA channel map select 0 */
#define UDMA_CHMAP1 0x400FF514 /**< DMA channel map select 1 */
#define UDMA_CHMAP2 0x400FF518 /**< DMA channel map select 2 */
#define UDMA_CHMAP3 0x400FF51C /**< DMA channel map select 3 */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name UDMA_STAT register bit masks
* @{
*/
#define UDMA_STAT_DMACHANS 0x001F0000 /**< Available uDMA channels minus 1 */
#define UDMA_STAT_STATE 0x000000F0 /**< Control state machine status */
#define UDMA_STAT_MASTEN 0x00000001 /**< Master enable status */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name UDMA_CFG register bit masks
* @{
*/
#define UDMA_CFG_MASTEN 0x00000001 /**< Controller master enable */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name UDMA_CTLBASE register bit masks
* @{
*/
#define UDMA_CTLBASE_ADDR 0xFFFFFC00 /**< Channel control base address */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name UDMA_ALTBASE register bit masks
* @{
*/
#define UDMA_ALTBASE_ADDR 0xFFFFFFFF /**< Alternate channel address pointer */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name UDMA_WAITSTAT register bit masks
* @{
*/
#define UDMA_WAITSTAT_WAITREQ 0xFFFFFFFF /**< Channel [n] wait status */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name UDMA_SWREQ register bit masks
* @{
*/
#define UDMA_SWREQ_SWREQ 0xFFFFFFFF /**< Channel [n] software request */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name UDMA_USEBURSTSET register bit masks
* @{
*/
#define UDMA_USEBURSTSET_SET 0xFFFFFFFF /**< Channel [n] useburst set */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name UDMA_USEBURSTCLR register bit masks
* @{
*/
#define UDMA_USEBURSTCLR_CLR 0xFFFFFFFF /**< Channel [n] useburst clear */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name UDMA_REQMASKSET register bit masks
* @{
*/
#define UDMA_REQMASKSET_SET 0xFFFFFFFF /**< Channel [n] request mask set */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name UDMA_REQMASKCLR register bit masks
* @{
*/
#define UDMA_REQMASKCLR_CLR 0xFFFFFFFF /**< Channel [n] request mask clear */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name UDMA_ENASET register bit masks
* @{
*/
#define UDMA_ENASET_SET 0xFFFFFFFF /**< Channel [n] enable set */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name UDMA_ENACLR register bit masks
* @{
*/
#define UDMA_ENACLR_CLR 0xFFFFFFFF /**< Channel [n] enable clear */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name UDMA_ALTSET register bit masks
* @{
*/
#define UDMA_ALTSET_SET 0xFFFFFFFF /**< Channel [n] alternate set */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name UDMA_ALTCLR register bit masks
* @{
*/
#define UDMA_ALTCLR_CLR 0xFFFFFFFF /**< Channel [n] alternate clear */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name UDMA_PRIOSET register bit masks
* @{
*/
#define UDMA_PRIOSET_SET 0xFFFFFFFF /**< Channel [n] priority set */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name UDMA_PRIOCLR register bit masks
* @{
*/
#define UDMA_PRIOCLR_CLR 0xFFFFFFFF /**< Channel [n] priority clear */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name UDMA_ERRCLR register bit masks
* @{
*/
#define UDMA_ERRCLR_ERRCLR 0x00000001 /**< uDMA bus error status */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name UDMA_CHASGN register bit masks
* @{
*/
#define UDMA_CHASGN_CHASGN 0xFFFFFFFF /**< Channel [n] assignment select */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name UDMA_CHIS register bit masks
* @{
*/
#define UDMA_CHIS_CHIS 0xFFFFFFFF /**< Channel [n] interrupt status */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name UDMA_CHMAP0 register bit masks
* @{
*/
#define UDMA_CHMAP0_CH7SEL 0xF0000000 /**< uDMA channel 7 source select */
#define UDMA_CHMAP0_CH6SEL 0x0F000000 /**< uDMA channel 6 source select */
#define UDMA_CHMAP0_CH5SEL 0x00F00000 /**< uDMA channel 5 source select */
#define UDMA_CHMAP0_CH4SEL 0x000F0000 /**< uDMA channel 4 source select */
#define UDMA_CHMAP0_CH3SEL 0x0000F000 /**< uDMA channel 3 source select */
#define UDMA_CHMAP0_CH2SEL 0x00000F00 /**< uDMA channel 2 source select */
#define UDMA_CHMAP0_CH1SEL 0x000000F0 /**< uDMA channel 1 source select */
#define UDMA_CHMAP0_CH0SEL 0x0000000F /**< uDMA channel 0 source select */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name UDMA_CHMAP1 register bit masks
* @{
*/
#define UDMA_CHMAP1_CH15SEL 0xF0000000 /**< uDMA channel 15 source select */
#define UDMA_CHMAP1_CH14SEL 0x0F000000 /**< uDMA channel 14 source select */
#define UDMA_CHMAP1_CH13SEL 0x00F00000 /**< uDMA channel 13 source select */
#define UDMA_CHMAP1_CH12SEL 0x000F0000 /**< uDMA channel 12 source select */
#define UDMA_CHMAP1_CH11SEL 0x0000F000 /**< uDMA channel 11 source select */
#define UDMA_CHMAP1_CH10SEL 0x00000F00 /**< uDMA channel 10 source select */
#define UDMA_CHMAP1_CH9SEL 0x000000F0 /**< uDMA channel 9 source select */
#define UDMA_CHMAP1_CH8SEL 0x0000000F /**< uDMA channel 8 source select */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name UDMA_CHMAP2 register bit masks
* @{
*/
#define UDMA_CHMAP2_CH23SEL 0xF0000000 /**< uDMA channel 23 source select */
#define UDMA_CHMAP2_CH22SEL 0x0F000000 /**< uDMA channel 22 source select */
#define UDMA_CHMAP2_CH21SEL 0x00F00000 /**< uDMA channel 21 source select */
#define UDMA_CHMAP2_CH20SEL 0x000F0000 /**< uDMA channel 20 source select */
#define UDMA_CHMAP2_CH19SEL 0x0000F000 /**< uDMA channel 19 source select */
#define UDMA_CHMAP2_CH18SEL 0x00000F00 /**< uDMA channel 18 source select */
#define UDMA_CHMAP2_CH17SEL 0x000000F0 /**< uDMA channel 17 source select */
#define UDMA_CHMAP2_CH16SEL 0x0000000F /**< uDMA channel 16 source select */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name UDMA_CHMAP3 register bit masks
* @{
*/
#define UDMA_CHMAP3_CH31SEL 0xF0000000 /**< uDMA channel 31 source select */
#define UDMA_CHMAP3_CH30SEL 0x0F000000 /**< uDMA channel 30 source select */
#define UDMA_CHMAP3_CH29SEL 0x00F00000 /**< uDMA channel 29 source select */
#define UDMA_CHMAP3_CH28SEL 0x000F0000 /**< uDMA channel 28 source select */
#define UDMA_CHMAP3_CH27SEL 0x0000F000 /**< uDMA channel 27 source select */
#define UDMA_CHMAP3_CH26SEL 0x00000F00 /**< uDMA channel 26 source select */
#define UDMA_CHMAP3_CH25SEL 0x000000F0 /**< uDMA channel 25 source select */
#define UDMA_CHMAP3_CH24SEL 0x0000000F /**< uDMA channel 24 source select */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name uDMA Channel encoding assignments
* @{
*/
/* Channel 0 */
#define UDMA_CH0_RESERVED0 0x00
#define UDMA_CH0_RESERVED1 0x01
#define UDMA_CH0_RESERVED2 0x02
#define UDMA_CH0_RESERVED3 0x03
#define UDMA_CH0_USB 0x04
/* Channel 1 */
#define UDMA_CH1_RESERVED0 0x00
#define UDMA_CH1_RESERVED1 0x01
#define UDMA_CH1_RESERVED2 0x02
#define UDMA_CH1_RESERVED3 0x03
#define UDMA_CH1_ADC 0x04
/* Channel 2 */
#define UDMA_CH2_RESERVED0 0x00
#define UDMA_CH2_TIMER3A 0x01
#define UDMA_CH2_RESERVED2 0x02
#define UDMA_CH2_RESERVED3 0x03
#define UDMA_CH2_FLASH 0x04
/* Channel 3 */
#define UDMA_CH3_RESERVED0 0x00
#define UDMA_CH3_TIMER3B 0x01
#define UDMA_CH3_RESERVED2 0x02
#define UDMA_CH3_RESERVED3 0x03
#define UDMA_CH3_RFCORETRG1 0x04
/* Channel 4 */
#define UDMA_CH4_RESERVED0 0x00
#define UDMA_CH4_TIMER2A 0x01
#define UDMA_CH4_RESERVED2 0x02
#define UDMA_CH4_RESERVED3 0x03
#define UDMA_CH4_RFCORETRG2 0x04
/* Channel 5 */
#define UDMA_CH5_RESERVED0 0x00
#define UDMA_CH5_TIMER2B 0x01
#define UDMA_CH5_RESERVED2 0x02
#define UDMA_CH5_RESERVED3 0x03
#define UDMA_CH5_RESERVED4 0x04
/* Channel 6 */
#define UDMA_CH6_RESERVED0 0x00
#define UDMA_CH6_TIMER2A 0x01
#define UDMA_CH6_RESERVED2 0x02
#define UDMA_CH6_RESERVED3 0x03
#define UDMA_CH6_RESERVED4 0x04
/* Channel 7 */
#define UDMA_CH7_RESERVED0 0x00
#define UDMA_CH7_TIMER2B 0x01
#define UDMA_CH7_RESERVED2 0x02
#define UDMA_CH7_RESERVED3 0x03
#define UDMA_CH7_RESERVED4 0x04
/* Channel 8 */
#define UDMA_CH8_UART0RX 0x00
#define UDMA_CH8_UART1RX 0x01
#define UDMA_CH8_RESERVED2 0x02
#define UDMA_CH8_RESERVED3 0x03
#define UDMA_CH8_RESERVED4 0x04
/* Channel 9 */
#define UDMA_CH9_UART0TX 0x00
#define UDMA_CH9_UART1TX 0x01
#define UDMA_CH9_RESERVED2 0x02
#define UDMA_CH9_RESERVED3 0x03
#define UDMA_CH9_RESERVED4 0x04
/* Channel 10 */
#define UDMA_CH10_SSI0RX 0x00
#define UDMA_CH10_SSI1RX 0x01
#define UDMA_CH10_RESERVED2 0x02
#define UDMA_CH10_RESERVED3 0x03
#define UDMA_CH10_RESERVED4 0x04
/* Channel 11 */
#define UDMA_CH11_SSI0TX 0x00
#define UDMA_CH11_SSI1TX 0x01
#define UDMA_CH11_RESERVED2 0x02
#define UDMA_CH11_RESERVED3 0x03
#define UDMA_CH11_RESERVED4 0x04
/* Channel 12 */
#define UDMA_CH12_RESERVED0 0x00
#define UDMA_CH12_RESERVED1 0x01
#define UDMA_CH12_RESERVED2 0x02
#define UDMA_CH12_RESERVED3 0x03
#define UDMA_CH12_RESERVED4 0x04
/* Channel 13 */
#define UDMA_CH13_RESERVED0 0x00
#define UDMA_CH13_RESERVED1 0x01
#define UDMA_CH13_RESERVED2 0x02
#define UDMA_CH13_RESERVED3 0x03
#define UDMA_CH13_RESERVED4 0x04
/* Channel 14 */
#define UDMA_CH14_ADC0 0x00
#define UDMA_CH14_TIMER2A 0x01
#define UDMA_CH14_RESERVED2 0x02
#define UDMA_CH14_RESERVED3 0x03
#define UDMA_CH14_RESERVED4 0x04
/* Channel 15 */
#define UDMA_CH15_ADC1 0x00
#define UDMA_CH15_TIMER2B 0x01
#define UDMA_CH15_RESERVED2 0x02
#define UDMA_CH15_RESERVED3 0x03
#define UDMA_CH15_RESERVED4 0x04
/* Channel 16 */
#define UDMA_CH16_ADC2 0x00
#define UDMA_CH16_RESERVED1 0x01
#define UDMA_CH16_RESERVED2 0x02
#define UDMA_CH16_RESERVED3 0x03
#define UDMA_CH16_RESERVED4 0x04
/* Channel 17 */
#define UDMA_CH17_ADC3 0x00
#define UDMA_CH17_RESERVED1 0x01
#define UDMA_CH17_RESERVED2 0x02
#define UDMA_CH17_RESERVED3 0x03
#define UDMA_CH17_RESERVED4 0x04
/* Channel 18 */
#define UDMA_CH18_TIMER0A 0x00
#define UDMA_CH18_TIMER1A 0x01
#define UDMA_CH18_RESERVED2 0x02
#define UDMA_CH18_RESERVED3 0x03
#define UDMA_CH18_RESERVED4 0x04
/* Channel 19 */
#define UDMA_CH19_TIMER0B 0x00
#define UDMA_CH19_TIMER1B 0x01
#define UDMA_CH19_RESERVED2 0x02
#define UDMA_CH19_RESERVED3 0x03
#define UDMA_CH19_RESERVED4 0x04
/* Channel 20 */
#define UDMA_CH20_TIMER1A 0x00
#define UDMA_CH20_RESERVED1 0x01
#define UDMA_CH20_RESERVED2 0x02
#define UDMA_CH20_RESERVED3 0x03
#define UDMA_CH20_RESERVED4 0x04
/* Channel 21 */
#define UDMA_CH21_TIMER1B 0x00
#define UDMA_CH21_RESERVED1 0x01
#define UDMA_CH21_RESERVED2 0x02
#define UDMA_CH21_RESERVED3 0x03
#define UDMA_CH21_RESERVED4 0x04
/* Channel 22 */
#define UDMA_CH22_UART1RX 0x00
#define UDMA_CH22_RESERVED1 0x01
#define UDMA_CH22_RESERVED2 0x02
#define UDMA_CH22_RESERVED3 0x03
#define UDMA_CH22_RESERVED4 0x04
/* Channel 23 */
#define UDMA_CH23_UART1TX 0x00
#define UDMA_CH23_RESERVED1 0x01
#define UDMA_CH23_RESERVED2 0x02
#define UDMA_CH23_RESERVED3 0x03
#define UDMA_CH23_RESERVED4 0x04
/* Channel 24 */
#define UDMA_CH24_SSI1RX 0x00
#define UDMA_CH24_ADC4 0x01
#define UDMA_CH24_RESERVED2 0x02
#define UDMA_CH24_RESERVED3 0x03
#define UDMA_CH24_RESERVED4 0x04
/* Channel 25 */
#define UDMA_CH25_SSI1TX 0x00
#define UDMA_CH25_ADC5 0x01
#define UDMA_CH25_RESERVED2 0x02
#define UDMA_CH25_RESERVED3 0x03
#define UDMA_CH25_RESERVED4 0x04
/* Channel 26 */
#define UDMA_CH26_RESERVED0 0x00
#define UDMA_CH26_ADC6 0x01
#define UDMA_CH26_RESERVED2 0x02
#define UDMA_CH26_RESERVED3 0x03
#define UDMA_CH26_RESERVED4 0x04
/* Channel 27 */
#define UDMA_CH27_RESERVED0 0x00
#define UDMA_CH27_ADC7 0x01
#define UDMA_CH27_RESERVED2 0x02
#define UDMA_CH27_RESERVED3 0x03
#define UDMA_CH27_RESERVED4 0x04
/* Channel 28 */
#define UDMA_CH28_RESERVED0 0x00
#define UDMA_CH28_RESERVED1 0x01
#define UDMA_CH28_RESERVED2 0x02
#define UDMA_CH28_RESERVED3 0x03
#define UDMA_CH28_RESERVED4 0x04
/* Channel 29 */
#define UDMA_CH29_RESERVED0 0x00
#define UDMA_CH29_RESERVED1 0x01
#define UDMA_CH29_RESERVED2 0x02
#define UDMA_CH29_RESERVED3 0x03
#define UDMA_CH29_RFCORET2TRG1 0x04
/* Channel 30 */
#define UDMA_CH30_SW 0x00
#define UDMA_CH30_RESERVED1 0x01
#define UDMA_CH30_RESERVED2 0x02
#define UDMA_CH30_RESERVED3 0x03
#define UDMA_CH30_RFCORET2TRG2 0x04
/* Channel 31 */
#define UDMA_CH31_RESERVED0 0x00
#define UDMA_CH31_RESERVED1 0x01
#define UDMA_CH31_RESERVED2 0x02
#define UDMA_CH31_RESERVED3 0x03
#define UDMA_CH31_RESERVED4 0x04
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name Values to ORd together as the ctrl argument of
* udma_set_channel_control_word()
* @{
*/
#define UDMA_CHCTL_DSTINC_NONE 0xC0000000 /**< Dst address no increment */
#define UDMA_CHCTL_DSTINC_32 0x80000000 /**< Dst address increment 32 bit */
#define UDMA_CHCTL_DSTINC_16 0x40000000 /**< Dst address increment 16 bit */
#define UDMA_CHCTL_DSTINC_8 0x00000000 /**< Dst address increment 8 bit */
#define UDMA_CHCTL_DSTSIZE_32 0x20000000 /**< Destination size 32 bit */
#define UDMA_CHCTL_DSTSIZE_16 0x10000000 /**< Destination size 16 bit */
#define UDMA_CHCTL_DSTSIZE_8 0x00000000 /**< Destination size 8 bit */
#define UDMA_CHCTL_SRCINC_NONE 0x0C000000 /**< Source address no increment */
#define UDMA_CHCTL_SRCINC_32 0x08000000 /**< Source address increment 32 bit */
#define UDMA_CHCTL_SRCINC_16 0x04000000 /**< Source address increment 16 bit */
#define UDMA_CHCTL_SRCINC_8 0x00000000 /**< Source address increment 8 bit */
#define UDMA_CHCTL_SRCSIZE_32 0x02000000 /**< Source size 32 bit */
#define UDMA_CHCTL_SRCSIZE_16 0x01000000 /**< Source size 16 bit */
#define UDMA_CHCTL_SRCSIZE_8 0x00000000 /**< Source size 8 bit */
#define UDMA_CHCTL_ARBSIZE_1 0x00000000 /**< Arbitration size 1 Transfer */
#define UDMA_CHCTL_ARBSIZE_2 0x00004000 /**< Arbitration size 2 Transfers */
#define UDMA_CHCTL_ARBSIZE_4 0x00008000 /**< Arbitration size 4 Transfers */
#define UDMA_CHCTL_ARBSIZE_8 0x0000C000 /**< Arbitration size 8 Transfers */
#define UDMA_CHCTL_ARBSIZE_16 0x00010000 /**< Arbitration size 16 Transfers */
#define UDMA_CHCTL_ARBSIZE_32 0x00014000 /**< Arbitration size 32 Transfers */
#define UDMA_CHCTL_ARBSIZE_64 0x00018000 /**< Arbitration size 64 Transfers */
#define UDMA_CHCTL_ARBSIZE_128 0x0001C000 /**< Arbitration size 128 Transfers */
#define UDMA_CHCTL_ARBSIZE_256 0x00020000 /**< Arbitration size 256 Transfers */
#define UDMA_CHCTL_ARBSIZE_512 0x00024000 /**< Arbitration size 512 Transfers */
#define UDMA_CHCTL_ARBSIZE_1024 0x00028000 /**< Arbitration size 1024 Transfers */
#define UDMA_CHCTL_XFERMODE_STOP 0x00000000 /**< Stop */
#define UDMA_CHCTL_XFERMODE_BASIC 0x00000001 /**< Basic */
#define UDMA_CHCTL_XFERMODE_AUTO 0x00000002 /**< Auto-Request */
#define UDMA_CHCTL_XFERMODE_PINGPONG 0x00000003 /**< Ping-Pong */
#define UDMA_CHCTL_XFERMODE_MEM_SG 0x00000004 /**< Memory Scatter-Gather */
#define UDMA_CHCTL_XFERMODE_MEM_SGA 0x00000005 /**< Memory Scatter-Gather Alt */
#define UDMA_CHCTL_XFERMODE_PER_SG 0x00000006 /**< Peripheral Scatter-Gather */
#define UDMA_CHCTL_XFERMODE_PER_SGA 0x00000007 /**< Peripheral Scatter-Gather Alt */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \brief Initialise the uDMA driver
*
* Prepares the channel control structure and enables the controller
*/
void udma_init(void);
/**
* \brief Sets the channels source address
* \param channel The channel as a value in [0 , UDMA_CONF_MAX_CHANNEL]
* \param
*/
void udma_set_channel_src(uint8_t channel, uint32_t src_end);
/**
* \brief
* \param channel The channel as a value in [0 , UDMA_CONF_MAX_CHANNEL]
*/
void udma_set_channel_dst(uint8_t channel, uint32_t dst_end);
/**
* \brief Configure the channel's control word
* \param channel The channel as a value in [0 , UDMA_CONF_MAX_CHANNEL]
* \param ctrl The value of the control word
*
* The value of the control word is generated by ORing the values defined as
* UDMA_CHCTL_xyz
*
* For example, to configure a channel with 8 bit source and destination size,
* 0 source increment and 8 bit destination increment, one would need to pass
* UDMA_CHCTL_DSTINC_8 | UDMA_CHCTL_SRCINC_NONE | UDMA_CHCTL_SRCSIZE_8 |
* UDMA_CHCTL_DSTSIZE_8
*
* Macros defined as 0 can be omitted.
*/
void udma_set_channel_control_word(uint8_t channel, uint32_t ctrl);
/**
* \brief Choose an encoding for a uDMA channel
* \param channel The channel as a value in [0 , UDMA_CONF_MAX_CHANNEL]
* \param enc A value in [0 , 4]
*
* Possible values for the \e encoding param are defined as UDMA_CHnn_xyz
*/
void udma_set_channel_assignment(uint8_t channel, uint8_t enc);
/**
* \brief Enables a uDMA channel
* \param channel The channel as a value in [0 , UDMA_CONF_MAX_CHANNEL]
*/
void udma_channel_enable(uint8_t channel);
/**
* \brief Disables a uDMA channel
* \param channel The channel as a value in [0 , UDMA_CONF_MAX_CHANNEL]
*/
void udma_channel_disable(uint8_t channel);
/**
* \brief Use the alternate control data structure for a channel
* \param channel The channel as a value in [0 , UDMA_CONF_MAX_CHANNEL]
*
* \note Currently, the driver only reserves memory space for primary contrl
* data structures
*/
void udma_channel_use_alternate(uint8_t channel);
/**
* \brief Use the primary control data structure for a channel
* \param channel The channel as a value in [0 , UDMA_CONF_MAX_CHANNEL]
*/
void udma_channel_use_primary(uint8_t channel);
/**
* \brief Set a uDMA channel to high priority
* \param channel The channel as a value in [0 , UDMA_CONF_MAX_CHANNEL]
*/
void udma_channel_prio_set_high(uint8_t channel);
/**
* \brief Set a uDMA channel to default priority
* \param channel The channel as a value in [0 , UDMA_CONF_MAX_CHANNEL]
*/
void udma_channel_prio_set_default(uint8_t channel);
/**
* \brief Configure a channel to only use burst transfers
* \param channel The channel as a value in [0 , UDMA_CONF_MAX_CHANNEL]
*
* \note The uDMA controller may under certain conditions automatically disable
* burst mode, in which case this function will need to be called again to
* re-enable them
*/
void udma_channel_use_burst(uint8_t channel);
/**
* \brief Configure a channel to use single as well as burst requests
* \param channel The channel as a value in [0 , UDMA_CONF_MAX_CHANNEL]
*/
void udma_channel_use_single(uint8_t channel);
/**
* \brief Disable peripheral triggers for a uDMA channel
* \param channel The channel as a value in [0 , UDMA_CONF_MAX_CHANNEL]
*
* Calling this function will result in the uDMA controller not acknowledging
* peripheral-generated transfer triggers. Afterwards, the channel may be used
* with software triggers
*/
void udma_channel_mask_set(uint8_t channel);
/**
* \brief Enable peripheral triggers for a uDMA channel
* \param channel The channel as a value in [0 , UDMA_CONF_MAX_CHANNEL]
*/
void udma_channel_mask_clr(uint8_t channel);
/**
* \brief Generate a software trigger to start a transfer
* \param channel The channel as a value in [0 , UDMA_CONF_MAX_CHANNEL]
*/
void udma_channel_sw_request(uint8_t channel);
/**
* \brief Retrieve the current mode for a channel
* \param channel The channel as a value in [0 , UDMA_CONF_MAX_CHANNEL]
* \return The channel's current mode
*
* The return value will be one of the UDMA_CHCTL_XFERMODE_xyz defines. This
* function is useful to determine whether a uDMA transfer has completed, in
* which case the return value will be UDMA_CHCTL_XFERMODE_STOP
*/
uint8_t udma_channel_get_mode(uint8_t channel);
/**
* \brief Calculate the value of the xfersize field in the control structure
* \param len The number of items to be transferred
* \return The value to be written to the control structure to achieve the
* desired transfer size
*
* If we want to transfer \e len items, we will normally do something like
* udma_set_channel_control_word(OTHER_FLAGS | udma_xfer_size(len))
*/
#define udma_xfer_size(len) ((len - 1) << 4)
#endif /* UDMA_H_ */
/**
* @}
* @}
*/

355
cpu/cc2538/dev/usb-regs.h Normal file
View File

@ -0,0 +1,355 @@
/*
* 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 cc2538
* @{
*
* \defgroup cc2538-usb cc2538 USB controller
*
* Driver for the cc2538 USB controller.
*
* We use the USB core in cpu/cc253x/usb which is known to work on Linux as
* well as on OS X.
* @{
*
* \file
* Header file with declarations for the cc2538 USB registers
*/
#ifndef USB_REGS_H_
#define USB_REGS_H_
#include "contiki-conf.h"
/*---------------------------------------------------------------------------*/
/**
* \name USB Register Offsets
* @{
*/
#define USB_ADDR 0x40089000 /**< Function address */
#define USB_POW 0x40089004 /**< Power/Control register */
#define USB_IIF 0x40089008 /**< IN EPs and EP0 interrupt flags */
#define USB_OIF 0x40089010 /**< OUT endpoint interrupt flags */
#define USB_CIF 0x40089018 /**< Common USB interrupt flags */
#define USB_IIE 0x4008901C /**< IN EPs and EP0 interrupt mask */
#define USB_OIE 0x40089024 /**< Out EPs interrupt-enable mask */
#define USB_CIE 0x4008902C /**< Common USB interrupt mask */
#define USB_FRML 0x40089030 /**< Current frame number (low byte) */
#define USB_FRMH 0x40089034 /**< Current frame number (high) */
#define USB_INDEX 0x40089038 /**< Current endpoint index register */
#define USB_CTRL 0x4008903C /**< USB control register */
#define USB_MAXI 0x40089040 /**< MAX packet size for IN EPs{1-5} */
#define USB_CS0_CSIL 0x40089044 /**< EP0 Control and Status or IN EPs
control and status (low) */
#define USB_CS0 0x40089044 /**< EP0 Control and Status
(Alias for USB_CS0_CSIL) */
#define USB_CSIL 0x40089044 /**< IN EPs control and status (low)
(Alias for USB_CS0_CSIL) */
#define USB_CSIH 0x40089048 /**< IN EPs control and status (high) */
#define USB_MAXO 0x4008904C /**< MAX packet size for OUT EPs */
#define USB_CSOL 0x40089050 /**< OUT EPs control and status (low) */
#define USB_CSOH 0x40089054 /**< OUT EPs control and status (high) */
#define USB_CNT0_CNTL 0x40089058 /**< Number of RX bytes in EP0 FIFO
or number of bytes in EP{1-5}
OUT FIFO (low) */
#define USB_CNT0 0x40089058 /**< Number of RX bytes in EP0 FIFO
(Alias for USB_CNT0_CNTL) */
#define USB_CNTL 0x40089058 /**< Number of bytes in EP{1-5}
OUT FIFO (low)
(Alias for USB_CNT0_CNTL) */
#define USB_CNTH 0x4008905C /**< Number of bytes in EP{1-5}
OUT FIFO (high) */
#define USB_F0 0x40089080 /**< Endpoint-0 FIFO */
#define USB_F1 0x40089088 /**< Endpoint-1 FIFO */
#define USB_F2 0x40089090 /**< Endpoint-2 FIFO */
#define USB_F3 0x40089098 /**< Endpoint-3 FIFO */
#define USB_F4 0x400890A0 /**< Endpoint-4 FIFO */
#define USB_F5 0x400890A8 /**< Endpoint-5 FIFO */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name USB_ADDR Register Bit-Masks
* @{
*/
#define USB_ADDR_UPDATE 0x00000080 /**< 1 while address updating */
#define USB_ADDR_USBADDR 0x0000007F /**< Device address */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name USB_POW Register Bit-Masks
* @{
*/
#define USB_POW_ISO_WAIT_SOF 0x00000080 /**< 1 until SOF received - ISO only */
#define USB_POW_RST 0x00000008 /**< 1 During reset signaling */
#define USB_POW_RESUME 0x00000004 /**< Remote wakeup resume signalling */
#define USB_POW_SUSPEND 0x00000002 /**< Suspend mode entered */
#define USB_POW_SUSPEND_EN 0x00000001 /**< Suspend enable */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name USB_IIF Register Bit-Masks
* @{
*/
#define USB_IIF_INEP5IF 0x00000020 /**< IN EP5 Interrupt flag */
#define USB_IIF_INEP4IF 0x00000010 /**< IN EP4 Interrupt flag */
#define USB_IIF_INEP3IF 0x00000008 /**< IN EP3 Interrupt flag */
#define USB_IIF_INEP2IF 0x00000004 /**< IN EP2 Interrupt flag */
#define USB_IIF_INEP1IF 0x00000002 /**< IN EP1 Interrupt flag */
#define USB_IIF_EP0IF 0x00000001 /**< EP0 Interrupt flag */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name USB_OIF Register Bit-Masks
* @{
*/
#define USB_OIF_OUTEP5IF 0x00000020 /**< OUT EP5 Interrupt flag */
#define USB_OIF_OUTEP4IF 0x00000010 /**< OUT EP4 Interrupt flag */
#define USB_OIF_OUTEP3IF 0x00000008 /**< OUT EP3 Interrupt flag */
#define USB_OIF_OUTEP2IF 0x00000004 /**< OUT EP2 Interrupt flag */
#define USB_OIF_OUTEP1IF 0x00000002 /**< OUT EP1 Interrupt flag */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name USB_CIF Register Bit-Masks
* @{
*/
#define USB_CIF_SOFIF 0x00000008 /**< Start-of-frame interrupt flag */
#define USB_CIF_RSTIF 0x00000004 /**< Reset interrupt flag */
#define USB_CIF_RESUMEIF 0x00000002 /**< Resume interrupt flag */
#define USB_CIF_SUSPENDIF 0x00000001 /**< Suspend interrupt flag */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name USB_IIE Register Bit-Masks
* @{
*/
#define USB_IIE_INEP5IE 0x00000020 /**< IN EP5 interrupt enable */
#define USB_IIE_INEP4IE 0x00000010 /**< IN EP4 interrupt enable */
#define USB_IIE_INEP3IE 0x00000008 /**< IN EP3 interrupt enable */
#define USB_IIE_INEP2IE 0x00000004 /**< IN EP2 interrupt enable */
#define USB_IIE_INEP1IE 0x00000002 /**< IN EP1 interrupt enable */
#define USB_IIE_EP0IE 0x00000001 /**< EP0 interrupt enable */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name USB_OIE Register Bit-Masks
* @{
*/
#define USB_OIE_OUTEP5IE 0x00000020 /**< OUT EP5 interrupt enable */
#define USB_OIE_OUTEP4IE 0x00000010 /**< OUT EP4 interrupt enable */
#define USB_OIE_OUTEP3IE 0x00000008 /**< OUT EP3 interrupt enable */
#define USB_OIE_OUTEP2IE 0x00000004 /**< OUT EP2 interrupt enable */
#define USB_OIE_OUTEP1IE 0x00000002 /**< OUT EP1 interrupt enable */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name USB_CIE Register Bit-Masks
* @{
*/
#define USB_CIE_SOFIE 0x00000008 /**< Start-of-frame interrupt enable */
#define USB_CIE_RSTIE 0x00000004 /**< Reset interrupt enable */
#define USB_CIE_RESUMEIE 0x00000002 /**< Resume interrupt enable */
#define USB_CIE_SUSPENDIE 0x00000001 /**< Suspend interrupt enable */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name USB_FRML Register Bit-Masks
* @{
*/
#define USB_FRML_FRAME 0x000000FF /**< Low byte of 11-bit frame number */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name USB_FRMH Register Bit-Masks
* @{
*/
#define USB_FRMH_FRAME 0x00000007 /**< 3 MSBs of 11-bit frame number */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name USB_INDEX Register Bit-Masks
* @{
*/
#define USB_INDEX_USBINDEX 0x0000000F /**< Endpoint selected */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name USB_CTRL Register Bit-Masks
* @{
*/
#define USB_CTRL_PLL_LOCKED 0x00000080 /**< PLL locked status */
#define USB_CTRL_PLL_EN 0x00000002 /**< 48-MHz USB PLL enable */
#define USB_CTRL_USB_EN 0x00000001 /**< USB enable */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name USB_MAXI Register Bit-Masks
* @{
*/
#define USB_MAXI_USBMAXI 0x000000FF /**< Maximum packet size */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name USB_CS0_CSIL Register Bit-Masks
* @{
*/
/** Listed as reserved in the UG, is this right? */
#define USB_CS0_CLR_SETUP_END 0x00000080
/** Deassert OUTPKT_RDY bit of this register or reset the data toggle to 0 */
#define USB_CS0_CSIL_CLR_OUTPKT_RDY_or_CLR_DATA_TOG 0x00000040
#define USB_CS0_CLR_OUTPKT_RDY 0x00000040
#define USB_CSIL_CLR_DATA_TOG 0x00000040
/**
* Set this bit to 1 to terminate the current transaction or
* is set when a STALL handshake has been sent
*/
#define USB_CS0_CSIL_SEND_STALL_or_SENT_STALL 0x00000020
#define USB_CS0_SEND_STALL 0x00000020
#define USB_CSIL_SENT_STALL 0x00000020
/**
* Is set if the control transfer ends due to a premature end-of-control
* transfer or set to 1 to make the USB controller reply with a STALL handshake
* when receiving IN tokens
*/
#define USB_CS0_CSIL_SETUP_END_or_SEND_STALL 0x00000010
#define USB_CS0_SETUP_END 0x00000010
#define USB_CSIL_SEND_STALL 0x00000010
/**
* Signal the end of a data transfer or set to 1 to flush next packet that
* is ready to transfer from the IN FIFO
*/
#define USB_CS0_CSIL_DATA_END_or_FLUSH_PACKET 0x00000008
#define USB_CS0_DATA_END 0x00000008
#define USB_CSIL_FLUSH_PACKET 0x00000008
/**
* Set when a STALL handshake is sent or set if an IN token is received when
* INPKT_RDY = 0, and a zero-length data packet is transmitted in response to
* the IN token. In bulk/interrupt mode, this bit is set when a NAK is returned
* in response to an IN token
*/
#define USB_CS0_CSIL_SENT_STALL_or_UNDERRUN 0x00000004
#define USB_CS0_SENT_STALL 0x00000004
#define USB_CSIL_UNDERRUN 0x00000004
/**
* Data packet has been loaded into the EP0 FIFO or at least one packet in the
* IN FIFO
*/
#define USB_CS0_CSIL_INPKT_RDY_or_PKT_PRESENT 0x00000002
#define USB_CS0_INPKT_RDY 0x00000002
#define USB_CSIL_PKT_PRESENT 0x00000002
/** Data packet received or data packet has been loaded into the IN FIFO */
#define USB_CS0_CSIL_OUTPKT_RDY_or_INPKT_RDY 0x00000001
#define USB_CS0_OUTPKT_RDY 0x00000001
#define USB_CSIL_INPKT_RDY 0x00000001
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name USB_CSIH Register Bit-Masks
* @{
*/
#define USB_CSIH_AUTISET 0x00000080 /**< Auto-assert INPKT_RDY */
#define USB_CSIH_ISO 0x00000040 /**< Selects IN endpoint type */
#define USB_CSIH_FORCE_DATA_TOG 0x00000008 /**< IN EP force data toggle switch */
#define USB_CSIH_IN_DBL_BUF 0x00000001 /**< Double buffering enable (IN FIFO) */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name USB_MAXO Register Bit-Masks
* @{
*/
#define USB_MAXO_USBMAXO 0x000000FF /**< Maximum packet size */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name USB_CSOL Register Bit-Masks
* @{
*/
#define USB_CSOL_CLR_DATA_TOG 0x00000080 /**< Setting resets data toggle to 0 */
#define USB_CSOL_SENT_STALL 0x00000040 /**< STALL handshake sent */
#define USB_CSOL_SEND_STALL 0x00000020 /**< Reply with STALL to OUT tokens */
#define USB_CSOL_FLUSH_PACKET 0x00000010 /**< Flush next packet read from OUT FIFO */
#define USB_CSOL_DATA_ERROR 0x00000008 /**< CRC or bit-stuff error in RX packet */
#define USB_CSOL_OVERRUN 0x00000004 /**< OUT packet can not be loaded into OUT FIFO */
#define USB_CSOL_FIFO_FULL 0x00000002 /**< OUT FIFO full */
#define USB_CSOL_OUTPKT_RDY 0x00000001 /**< OUT packet read in OUT FIFO */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name USB_CSOH Register Bit-Masks
* @{
*/
#define USB_CSOH_AUTOCLEAR 0x00000080 /**< Auto-clear OUTPKT_RDY */
#define USB_CSOH_ISO 0x00000040 /**< Selects OUT endpoint type */
#define USB_CSOH_OUT_DBL_BUF 0x00000001 /**< Double buffering enable (OUT FIFO) */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name USB_CNT0_CNTL Register Bit-Masks
* @{
*/
#define USB_CNT0_CNTL_USBCNT0 0x0000003F /**< Number of RX bytes in EP0 FIFO */
#define USB_CNT0_USBCNT0 0x0000003F
#define USB_CNT0_CNTL_USBCNT_5_0 0x0000003F /**< 6 LSBs of the number of RX
bytes in EP1-5 OUT FIFO */
#define USB_CNTL_USBCNT_5_0 0x0000003F
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name USB_CNTH Register Bit-Masks
* @{
*/
#define USB_CNTH_USBCNT 0x00000007 /**< 3 MSBs of RX byte number */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name USB_F[0-5] Register Bit-Masks
* @{
*/
#define USB_F0_USBF0 0x000000FF /**< Endpoint 0 FIFO mask */
#define USB_F1_USBF1 0x000000FF /**< Endpoint 1 FIFO mask */
#define USB_F2_USBF2 0x000000FF /**< Endpoint 2 FIFO mask */
#define USB_F3_USBF3 0x000000FF /**< Endpoint 3 FIFO mask */
#define USB_F4_USBF4 0x000000FF /**< Endpoint 4 FIFO mask */
#define USB_F5_USBF5 0x000000FF /**< Endpoint 5 FIFO mask */
/** @} */
#endif /* USB_REGS_H_ */
/**
* @}
* @}
*/

95
cpu/cc2538/dev/watchdog.c Normal file
View File

@ -0,0 +1,95 @@
/*
* 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 cc2538
* @{
*
* \defgroup cc2538-wdt cc2538 watchdog timer driver
*
* Driver for the cc2538 Watchdog Timer
* @{
*
* \file
* Implementation of the cc2538 watchdog driver. The peripheral runs in
* watchdog mode.
*/
#include "contiki.h"
#include "reg.h"
#include "cpu.h"
#include "dev/smwdthrosc.h"
/*---------------------------------------------------------------------------*/
/** \brief Initialisation function for the WDT. Currently simply explicitly
* sets the WDT interval to max interval */
void
watchdog_init(void)
{
/* Max interval, don't enable yet */
REG(SMWDTHROSC_WDCTL) = 0;
}
/*---------------------------------------------------------------------------*/
/** \brief Starts the WDT in watchdog mode, maximum interval */
void
watchdog_start(void)
{
/* Max interval (32768), watchdog mode, Enable */
REG(SMWDTHROSC_WDCTL) = SMWDTHROSC_WDCTL_EN;
}
/*---------------------------------------------------------------------------*/
/** \brief Writes the WDT clear sequence. This function assumes that we are
* in watchdog mode and that interval bits (bits [1:0]) are 00 */
void
watchdog_periodic(void)
{
/* Safe to write to bits [3:0] since EN is 1 */
REG(SMWDTHROSC_WDCTL) = (SMWDTHROSC_WDCTL_CLR_3 | SMWDTHROSC_WDCTL_CLR_1);
REG(SMWDTHROSC_WDCTL) = (SMWDTHROSC_WDCTL_CLR_2 | SMWDTHROSC_WDCTL_CLR_0);
}
/*---------------------------------------------------------------------------*/
/** \brief In watchdog mode, the WDT can not be stopped. This function is
* defined here to satisfy API requirements.
*/
void
watchdog_stop(void)
{
return;
}
/*---------------------------------------------------------------------------*/
/** \brief Keeps control until the WDT throws a reset signal */
void
watchdog_reboot(void)
{
INTERRUPTS_DISABLE();
while(1);
}
/**
* @}
* @}
*/

65
cpu/cc2538/ieee-addr.c Normal file
View File

@ -0,0 +1,65 @@
/*
* Copyright (c) 2013, 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 cc2538-ieee-addr
* @{
*
* \file
* Driver for the cc2538 IEEE addresses
*/
#include "contiki-conf.h"
#include "net/rime/rimeaddr.h"
#include "ieee-addr.h"
#include <stdint.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 {
/* Reading from Info Page, we need to invert byte order */
int i;
for(i = 0; i < len; i++) {
dst[i] = ((uint8_t *)IEEE_ADDR_LOCATION_PRIMARY)[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
}
/** @} */

80
cpu/cc2538/ieee-addr.h Normal file
View File

@ -0,0 +1,80 @@
/*
* Copyright (c) 2013, 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 cc2538
* @{
*
* \defgroup cc2538-ieee-addr cc2538 IEEE Address Control
*
* Driver for the retrieval of an IEEE address from flash
* @{
*
* \file
* Header file with register and macro declarations for the cc2538 IEEE address
* driver
*/
#ifndef IEEE_ADDR_H_
#define IEEE_ADDR_H_
#include "contiki-conf.h"
#include <stdint.h>
/*---------------------------------------------------------------------------*/
/**
* \name IEEE address locations
* @{
*/
#define IEEE_ADDR_LOCATION_PRIMARY 0x00280020 /**< IEEE address location */
/** @} */
/*---------------------------------------------------------------------------*/
/*
* \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
*
* The address will be read from an InfoPage location or a hard-coded address
* will be used, depending on the value of configuration parameter
* IEEE_ADDR_CONF_HARDCODED
*
* This function will copy \e len LS bytes
*
* The destination address will be populated with dst[0] holding the MSB and
* dst[len - 1] holding the LSB
*/
void ieee_addr_cpy_to(uint8_t *dst, uint8_t len);
#endif /* IEEE_ADDR_H_ */
/**
* @}
* @}
*/

316
cpu/cc2538/lpm.c Normal file
View File

@ -0,0 +1,316 @@
/*
* Copyright (c) 2013, 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 cc2538-lpm
* @{
*
* \file
* Implementation of low power modes ofr the cc2538
*/
#include "contiki-conf.h"
#include "sys/energest.h"
#include "sys/process.h"
#include "dev/sys-ctrl.h"
#include "dev/scb.h"
#include "dev/rfcore-xreg.h"
#include "dev/usb-regs.h"
#include "rtimer-arch.h"
#include "reg.h"
#include <stdint.h>
#include <string.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
/*---------------------------------------------------------------------------*/
/*
* Deep Sleep thresholds in rtimer ticks (~30.5 usec)
*
* If Deep Sleep duration < DEEP_SLEEP_PM1_THRESHOLD, simply enter PM0
* If duration < DEEP_SLEEP_PM2_THRESHOLD drop to PM1
* else PM2.
*/
#define DEEP_SLEEP_PM1_THRESHOLD 10
#define DEEP_SLEEP_PM2_THRESHOLD 100
/*---------------------------------------------------------------------------*/
#define assert_wfi() do { asm("wfi"::); } while(0)
/*---------------------------------------------------------------------------*/
#if LPM_CONF_STATS
rtimer_clock_t lpm_stats[3];
#define LPM_STATS_INIT() do { memset(lpm_stats, 0, sizeof(lpm_stats)); \
} while(0)
#define LPM_STATS_ADD(pm, val) do { lpm_stats[pm] += val; } while(0)
#else
#define LPM_STATS_INIT()
#define LPM_STATS_ADD(stat, val)
#endif
/*---------------------------------------------------------------------------*/
/*
* Remembers what time it was when went to deep sleep
* This is used when coming out of PM1/2 to adjust the system clock, which
* stops ticking while in those PMs
*/
static rtimer_clock_t sleep_enter_time;
#define RTIMER_CLOCK_TICK_RATIO (RTIMER_SECOND / CLOCK_SECOND)
void clock_adjust(clock_time_t ticks);
/*---------------------------------------------------------------------------*/
/* Stores the currently specified MAX allowed PM */
static uint8_t max_pm;
/*---------------------------------------------------------------------------*/
/*
* Routine to put is in PM0. We also need to do some housekeeping if the stats
* or the energest module is enabled
*/
static void
enter_pm0(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);
/*
* After PM0 we don't need to adjust the system clock. Thus, saving the time
* we enter Deep Sleep is only required if we are keeping stats.
*/
if(LPM_CONF_STATS) {
sleep_enter_time = RTIMER_NOW();
}
assert_wfi();
/* We reach here when the interrupt context that woke us up has returned */
LPM_STATS_ADD(0, RTIMER_NOW() - sleep_enter_time);
/* Remember IRQ energest for next pass */
ENERGEST_IRQ_SAVE(irq_energest);
ENERGEST_ON(ENERGEST_TYPE_CPU);
ENERGEST_OFF(ENERGEST_TYPE_LPM);
}
/*---------------------------------------------------------------------------*/
static void
select_32_mhz_xosc(void)
{
/* Turn on the 32 MHz XOSC and source the system clock on it. */
REG(SYS_CTRL_CLOCK_CTRL) &= ~SYS_CTRL_CLOCK_CTRL_OSC;
/* Wait for the switch to take place */
while((REG(SYS_CTRL_CLOCK_STA) & SYS_CTRL_CLOCK_STA_OSC) != 0);
}
/*---------------------------------------------------------------------------*/
static void
select_16_mhz_rcosc(void)
{
/*First, make sure there is no ongoing clock source change */
while((REG(SYS_CTRL_CLOCK_STA) & SYS_CTRL_CLOCK_STA_SOURCE_CHANGE) != 0);
/* Set the System Clock to use the 16MHz RC OSC */
REG(SYS_CTRL_CLOCK_CTRL) |= SYS_CTRL_CLOCK_CTRL_OSC;
/* Wait till it's happened */
while((REG(SYS_CTRL_CLOCK_STA) & SYS_CTRL_CLOCK_STA_OSC) == 0);
}
/*---------------------------------------------------------------------------*/
void
lpm_exit()
{
if((REG(SYS_CTRL_PMCTL) & SYS_CTRL_PMCTL_PM3) == SYS_CTRL_PMCTL_PM0) {
/* We either just exited PM0 or we were not sleeping in the first place.
* We don't need to do anything clever */
return;
}
LPM_STATS_ADD(REG(SYS_CTRL_PMCTL) & SYS_CTRL_PMCTL_PM3,
RTIMER_NOW() - sleep_enter_time);
/* Adjust the system clock, since it was not counting while we were sleeping
* We need to convert sleep duration from rtimer ticks to clock ticks and
* this will cost us some accuracy */
clock_adjust((clock_time_t)
((RTIMER_NOW() - sleep_enter_time) / RTIMER_CLOCK_TICK_RATIO));
/* Restore system clock to the 32 MHz XOSC */
select_32_mhz_xosc();
/* Restore PMCTL to PM0 for next pass */
REG(SYS_CTRL_PMCTL) = SYS_CTRL_PMCTL_PM0;
/* Remember IRQ energest for next pass */
ENERGEST_IRQ_SAVE(irq_energest);
ENERGEST_ON(ENERGEST_TYPE_CPU);
ENERGEST_OFF(ENERGEST_TYPE_LPM);
}
/*---------------------------------------------------------------------------*/
void
lpm_enter()
{
rtimer_clock_t lpm_exit_time;
rtimer_clock_t duration;
/*
* If either the RF or the USB is on, dropping to PM1/2 would equal pulling
* the rug (32MHz XOSC) from under their feet. Thus, we only drop to PM0.
* PM0 is also used if max_pm==0
*
* Note: USB Suspend/Resume/Remote Wake-Up are not supported. Once the PLL is
* on, it stays on.
*/
if((REG(RFCORE_XREG_FSMSTAT0) & RFCORE_XREG_FSMSTAT0_FSM_FFCTRL_STATE) != 0
|| REG(USB_CTRL) != 0 || max_pm == 0) {
enter_pm0();
/* We reach here when the interrupt context that woke us up has returned */
return;
}
/*
* USB PLL was off. Radio was off: Some Duty Cycling in place.
* rtimers run on the Sleep Timer. Thus, if we have a scheduled rtimer
* task, a Sleep Timer interrupt will fire and will wake us up.
* Choose the most suitable PM based on anticipated deep sleep duration
*/
lpm_exit_time = rtimer_arch_next_trigger();
duration = lpm_exit_time - RTIMER_NOW();
if(duration < DEEP_SLEEP_PM1_THRESHOLD || lpm_exit_time == 0) {
/* Anticipated duration too short or no scheduled rtimer task. Use PM0 */
enter_pm0();
/* We reach here when the interrupt context that woke us up has returned */
return;
}
/* If we reach here, we -may- (but may as well not) be dropping to PM1+. We
* know the USB and RF are off so we can switch to the 16MHz RCOSC. */
select_16_mhz_rcosc();
/*
* Switching the System Clock from the 32MHz XOSC to the 16MHz RC OSC may
* have taken a while. Re-estimate sleep duration.
*/
duration = lpm_exit_time - RTIMER_NOW();
if(duration < DEEP_SLEEP_PM1_THRESHOLD) {
/*
* oops... The clock switch took some time and now the remaining sleep
* duration is too short. Restore the clock source to the 32MHz XOSC and
* abort the LPM attempt altogether. We can't drop to PM0,
* we need to yield to main() since we may have events to service now.
*/
select_32_mhz_xosc();
return;
} else if(duration >= DEEP_SLEEP_PM2_THRESHOLD && max_pm == 2) {
/* Long sleep duration and PM2 is allowed. Use it */
REG(SYS_CTRL_PMCTL) = SYS_CTRL_PMCTL_PM2;
} else {
/*
* Anticipated duration too short for PM2 but long enough for PM1 and we
* are allowed to use PM1
*/
REG(SYS_CTRL_PMCTL) = SYS_CTRL_PMCTL_PM1;
}
/* 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);
/* Remember the current time so we can adjust the clock when we wake up */
sleep_enter_time = RTIMER_NOW();
/*
* Last chance to abort entering Deep Sleep.
*
* - There is the slight off-chance that a SysTick interrupt fired while we
* were trying to make up our mind. This may have raised an event.
* - The Sleep Timer may have fired
*
* Check if there is still a scheduled rtimer task and check for pending
* events before going to Deep Sleep
*/
if(process_nevents() || rtimer_arch_next_trigger() == 0) {
/* Event flag raised or rtimer inactive.
* Turn on the 32MHz XOSC