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(<