Merge branch 'contiki' into osd
This commit is contained in:
commit
877bf27f5a
245 changed files with 8117 additions and 6356 deletions
|
@ -117,7 +117,7 @@ makestrings(void)
|
|||
makeaddr(&addr, gateway);
|
||||
|
||||
#if WITH_DNS
|
||||
addrptr = resolv_getserver();
|
||||
addrptr = uip_nameserver_get(0);
|
||||
if(addrptr != NULL) {
|
||||
makeaddr(addrptr, dnsserver);
|
||||
}
|
||||
|
@ -245,7 +245,7 @@ dhcpc_configured(const struct dhcpc_state *s)
|
|||
uip_setnetmask(&s->netmask);
|
||||
uip_setdraddr(&s->default_router);
|
||||
#if WITH_DNS
|
||||
resolv_conf(&s->dnsaddr);
|
||||
uip_nameserver_update(&s->dnsaddr, UIP_NAMESERVER_INFINITE_LIFETIME);
|
||||
#endif /* WITH_DNS */
|
||||
|
||||
set_statustext("Configured.");
|
||||
|
@ -261,7 +261,7 @@ dhcpc_unconfigured(const struct dhcpc_state *s)
|
|||
uip_setnetmask(&nulladdr);
|
||||
uip_setdraddr(&nulladdr);
|
||||
#if WITH_DNS
|
||||
resolv_conf(&nulladdr);
|
||||
uip_nameserver_update(&nulladdr, UIP_NAMESERVER_INFINITE_LIFETIME);
|
||||
#endif /* WITH_DNS */
|
||||
|
||||
set_statustext("Unconfigured.");
|
||||
|
|
|
@ -105,7 +105,7 @@ config_read(char *filename)
|
|||
uip_setnetmask(&config.netmask);
|
||||
uip_setdraddr(&config.draddr);
|
||||
#if WITH_DNS
|
||||
resolv_conf(&config.resolvaddr);
|
||||
uip_nameserver_update(&config.resolvaddr, UIP_NAMESERVER_INFINITE_LIFETIME);
|
||||
#endif /* WITH_DNS */
|
||||
|
||||
return &config.ethernetcfg;
|
||||
|
|
|
@ -89,7 +89,7 @@ fixup: .byte fixup02-fixup01, fixup03-fixup02, fixup04-fixup03
|
|||
.byte fixup29-fixup28, fixup30-fixup29, fixup31-fixup30
|
||||
.byte fixup32-fixup31, fixup33-fixup32, fixup34-fixup33
|
||||
.byte fixup35-fixup34, fixup36-fixup35, fixup37-fixup36
|
||||
.byte fixup38-fixup37, fixup39-fixup38, fixup40-fixup39
|
||||
.byte fixup38-fixup37, fixup39-fixup38
|
||||
|
||||
fixups = * - fixup
|
||||
|
||||
|
@ -272,9 +272,7 @@ fixup22:lda ethdata
|
|||
bcs :++
|
||||
|
||||
; Yes, skip packet
|
||||
; Remove and release RX packet from the FIFO
|
||||
lda #%10000000
|
||||
fixup23:sta ethmmucr
|
||||
jsr releasepacket
|
||||
|
||||
; No packet available
|
||||
lda #$00
|
||||
|
@ -285,7 +283,7 @@ fixup23:sta ethmmucr
|
|||
; Read bytes into buffer
|
||||
: jsr adjustptr
|
||||
:
|
||||
fixup24:lda ethdata
|
||||
fixup23:lda ethdata
|
||||
sta (ptr),y
|
||||
iny
|
||||
bne :-
|
||||
|
@ -294,8 +292,7 @@ fixup24:lda ethdata
|
|||
bpl :-
|
||||
|
||||
; Remove and release RX packet from the FIFO
|
||||
lda #%10000000
|
||||
fixup25:sta ethmmucr
|
||||
jsr releasepacket
|
||||
|
||||
; Return packet length
|
||||
lda len
|
||||
|
@ -313,19 +310,19 @@ send:
|
|||
; Allocate memory for TX
|
||||
txa
|
||||
ora #%00100000
|
||||
fixup26:sta ethmmucr
|
||||
fixup24:sta ethmmucr
|
||||
|
||||
; 8 retries
|
||||
ldy #$08
|
||||
|
||||
; Wait for allocation ready
|
||||
:
|
||||
fixup27:lda ethist
|
||||
fixup25:lda ethist
|
||||
and #%00001000 ; ALLOC INT
|
||||
bne :+
|
||||
|
||||
; Shouldn't we do something here to actively free memory,
|
||||
; maybe removing and releasing an RX packet from the FIFO ???
|
||||
; No space avaliable, skip a received frame
|
||||
jsr releasepacket
|
||||
|
||||
; And try again
|
||||
dey
|
||||
|
@ -335,21 +332,21 @@ fixup27:lda ethist
|
|||
|
||||
; Acknowledge interrupt, is it necessary ???
|
||||
: lda #%00001000
|
||||
fixup28:sta ethack
|
||||
fixup26:sta ethack
|
||||
|
||||
; Set packet address
|
||||
fixup29:lda etharr
|
||||
fixup30:sta ethpnr
|
||||
fixup27:lda etharr
|
||||
fixup28:sta ethpnr
|
||||
|
||||
lda #$00
|
||||
ldx #%01000000 ; AUTO INCR.
|
||||
fixup31:sta ethptr
|
||||
fixup32:stx ethptr+1
|
||||
fixup29:sta ethptr
|
||||
fixup30:stx ethptr+1
|
||||
|
||||
; Status written by CSMA
|
||||
lda #$00
|
||||
fixup33:sta ethdata
|
||||
fixup34:sta ethdata
|
||||
fixup31:sta ethdata
|
||||
fixup32:sta ethdata
|
||||
|
||||
; Check packet length parity:
|
||||
; - Even packet length -> carry set -> add 6 bytes
|
||||
|
@ -361,10 +358,10 @@ fixup34:sta ethdata
|
|||
; The packet contains 3 extra words
|
||||
lda len
|
||||
adc #$05 ; Actually 5 or 6 depending on carry
|
||||
fixup35:sta ethdata
|
||||
fixup33:sta ethdata
|
||||
lda len+1
|
||||
adc #$00
|
||||
fixup36:sta ethdata
|
||||
fixup34:sta ethdata
|
||||
|
||||
; Send the packet
|
||||
; ---------------
|
||||
|
@ -372,7 +369,7 @@ fixup36:sta ethdata
|
|||
; Write bytes from buffer
|
||||
jsr adjustptr
|
||||
: lda (ptr),y
|
||||
fixup37:sta ethdata
|
||||
fixup35:sta ethdata
|
||||
iny
|
||||
bne :-
|
||||
inc ptr+1
|
||||
|
@ -390,13 +387,13 @@ fixup37:sta ethdata
|
|||
|
||||
; No
|
||||
: lda #$00
|
||||
fixup38:sta ethdata ; Fill byte
|
||||
fixup36:sta ethdata ; Fill byte
|
||||
:
|
||||
fixup39:sta ethdata ; Control byte
|
||||
fixup37:sta ethdata ; Control byte
|
||||
|
||||
; Add packet to FIFO
|
||||
lda #%11000000 ; ENQUEUE PACKET - transmit packet
|
||||
fixup40:sta ethmmucr
|
||||
fixup38:sta ethmmucr
|
||||
clc
|
||||
rts
|
||||
|
||||
|
@ -407,6 +404,14 @@ exit:
|
|||
|
||||
;---------------------------------------------------------------------
|
||||
|
||||
releasepacket:
|
||||
; Remove and release RX packet from the FIFO
|
||||
lda #%10000000
|
||||
fixup39:sta ethmmucr
|
||||
rts
|
||||
|
||||
;---------------------------------------------------------------------
|
||||
|
||||
adjustptr:
|
||||
lda len
|
||||
ldx len+1
|
||||
|
|
|
@ -402,14 +402,18 @@ sicslowmac_dataRequest(void)
|
|||
frame_create_params_t params;
|
||||
frame_result_t result;
|
||||
|
||||
#if NETSTACK_CONF_WITH_RIME
|
||||
/* Save the msduHandle in a global variable. */
|
||||
msduHandle = packetbuf_attr(PACKETBUF_ATTR_PACKET_ID);
|
||||
#endif
|
||||
|
||||
/* Build the FCF. */
|
||||
params.fcf.frameType = DATAFRAME;
|
||||
params.fcf.securityEnabled = false;
|
||||
params.fcf.framePending = false;
|
||||
#if NETSTACK_CONF_WITH_RIME
|
||||
params.fcf.ackRequired = packetbuf_attr(PACKETBUF_ATTR_RELIABLE);
|
||||
#endif
|
||||
params.fcf.panIdCompression = false;
|
||||
|
||||
/* Insert IEEE 802.15.4 (2003) version bit. */
|
||||
|
|
|
@ -1073,8 +1073,10 @@ rf230_transmit(unsigned short payload_len)
|
|||
|
||||
if (tx_result==RADIO_TX_OK) {
|
||||
RIMESTATS_ADD(lltx);
|
||||
#if NETSTACK_CONF_WITH_RIME
|
||||
if(packetbuf_attr(PACKETBUF_ATTR_RELIABLE))
|
||||
RIMESTATS_ADD(ackrx); //ack was requested and received
|
||||
#endif
|
||||
#if RF230_INSERTACK
|
||||
/* Not PAN broadcast to FFFF, and ACK was requested and received */
|
||||
if (!((buffer[5]==0xff) && (buffer[6]==0xff)) && (buffer[0]&(1<<6)))
|
||||
|
|
|
@ -49,8 +49,8 @@
|
|||
*
|
||||
*/
|
||||
|
||||
#ifndef RADIO_H
|
||||
#define RADIO_H
|
||||
#ifndef RF230BB_H_
|
||||
#define RF230BB_H_
|
||||
/*============================ INCLUDE =======================================*/
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
@ -225,6 +225,6 @@ uint8_t rf230_get_raw_rssi(void);
|
|||
|
||||
#define rf230_rssi rf230_get_raw_rssi
|
||||
|
||||
#endif
|
||||
#endif /* RF230BB_H_ */
|
||||
/** @} */
|
||||
/*EOF*/
|
||||
|
|
|
@ -52,12 +52,20 @@ CONTIKI_CPU_SOURCEFILES += nvic.c cpu.c sys-ctrl.c gpio.c ioc.c spi.c adc.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
|
||||
CONTIKI_CPU_SOURCEFILES += i2c.c cc2538-temp-sensor.c vdd3-sensor.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
|
||||
|
||||
ifneq ($(TARGET_START_SOURCEFILES),)
|
||||
CPU_START_SOURCEFILES = TARGET_START_SOURCEFILES
|
||||
else
|
||||
CPU_START_SOURCEFILES = startup-gcc.c
|
||||
endif
|
||||
CPU_STARTFILES = ${addprefix $(OBJECTDIR)/,${call oname, $(CPU_START_SOURCEFILES)}}
|
||||
|
||||
CONTIKI_SOURCEFILES += $(CONTIKI_CPU_SOURCEFILES) $(DEBUG_IO_SOURCEFILES)
|
||||
CONTIKI_SOURCEFILES += $(USB_CORE_SOURCEFILES) $(USB_ARCH_SOURCEFILES)
|
||||
|
||||
|
@ -74,7 +82,7 @@ $(OBJECTDIR)/ieee-addr.o: ieee-addr.c FORCE | $(OBJECTDIR)
|
|||
### Compilation rules
|
||||
CUSTOM_RULE_LINK=1
|
||||
|
||||
%.elf: $(TARGET_STARTFILES) %.co $(PROJECT_OBJECTFILES) $(PROJECT_LIBRARIES) contiki-$(TARGET).a $(LDSCRIPT)
|
||||
%.elf: $(CPU_STARTFILES) %.co $(PROJECT_OBJECTFILES) $(PROJECT_LIBRARIES) contiki-$(TARGET).a $(LDSCRIPT)
|
||||
$(TRACE_LD)
|
||||
$(Q)$(LD) $(LDFLAGS) ${filter-out $(LDSCRIPT) %.a,$^} ${filter %.a,$^} $(TARGET_LIBFILES) -o $@
|
||||
|
||||
|
|
|
@ -96,17 +96,17 @@ clock_init(void)
|
|||
REG(SYS_CTRL_RCGCGPT) |= SYS_CTRL_RCGCGPT_GPT0;
|
||||
|
||||
/* Make sure GPT0 is off */
|
||||
REG(GPT_0_BASE | GPTIMER_CTL) = 0;
|
||||
REG(GPT_0_BASE + GPTIMER_CTL) = 0;
|
||||
|
||||
|
||||
/* 16-bit */
|
||||
REG(GPT_0_BASE | GPTIMER_CFG) = 0x04;
|
||||
REG(GPT_0_BASE + GPTIMER_CFG) = 0x04;
|
||||
|
||||
/* One-Shot, Count Down, No Interrupts */
|
||||
REG(GPT_0_BASE | GPTIMER_TAMR) = GPTIMER_TAMR_TAMR_ONE_SHOT;
|
||||
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;
|
||||
REG(GPT_0_BASE + GPTIMER_TAPR) = 0x0F;
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
CCIF clock_time_t
|
||||
|
@ -144,11 +144,11 @@ clock_wait(clock_time_t i)
|
|||
void
|
||||
clock_delay_usec(uint16_t dt)
|
||||
{
|
||||
REG(GPT_0_BASE | GPTIMER_TAILR) = dt;
|
||||
REG(GPT_0_BASE | GPTIMER_CTL) |= GPTIMER_CTL_TAEN;
|
||||
REG(GPT_0_BASE + GPTIMER_TAILR) = dt;
|
||||
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);
|
||||
while(REG(GPT_0_BASE + GPTIMER_CTL) & GPTIMER_CTL_TAEN);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/**
|
||||
|
|
|
@ -80,7 +80,6 @@
|
|||
/* 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 */
|
||||
|
@ -180,6 +179,8 @@ get_channel()
|
|||
static int8_t
|
||||
set_channel(uint8_t channel)
|
||||
{
|
||||
uint8_t was_on = 0;
|
||||
|
||||
PRINTF("RF: Set Channel\n");
|
||||
|
||||
if((channel < CC2538_RF_CHANNEL_MIN) || (channel > CC2538_RF_CHANNEL_MAX)) {
|
||||
|
@ -189,16 +190,14 @@ set_channel(uint8_t channel)
|
|||
/* Changes to FREQCTRL take effect after the next recalibration */
|
||||
|
||||
/* If we are off, save state, otherwise switch off and save state */
|
||||
if((REG(RFCORE_XREG_FSMSTAT0) & RFCORE_XREG_FSMSTAT0_FSM_FFCTRL_STATE) == 0) {
|
||||
rf_flags |= WAS_OFF;
|
||||
} else {
|
||||
rf_flags &= ~WAS_OFF;
|
||||
if((REG(RFCORE_XREG_FSMSTAT0) & RFCORE_XREG_FSMSTAT0_FSM_FFCTRL_STATE) != 0) {
|
||||
was_on = 1;
|
||||
off();
|
||||
}
|
||||
REG(RFCORE_XREG_FREQCTRL) = (CC2538_RF_CHANNEL_MIN
|
||||
+ (channel - CC2538_RF_CHANNEL_MIN) * CC2538_RF_CHANNEL_SPACING);
|
||||
/* switch radio back on only if radio was on before - otherwise will turn on radio foor sleepy nodes */
|
||||
if((rf_flags & WAS_OFF) != WAS_OFF) {
|
||||
if(was_on) {
|
||||
on();
|
||||
}
|
||||
|
||||
|
@ -244,10 +243,11 @@ static radio_value_t
|
|||
get_rssi(void)
|
||||
{
|
||||
int8_t rssi;
|
||||
uint8_t was_off = 0;
|
||||
|
||||
/* If we are off, turn on first */
|
||||
if((REG(RFCORE_XREG_FSMSTAT0) & RFCORE_XREG_FSMSTAT0_FSM_FFCTRL_STATE) == 0) {
|
||||
rf_flags |= WAS_OFF;
|
||||
was_off = 1;
|
||||
on();
|
||||
}
|
||||
|
||||
|
@ -257,8 +257,7 @@ get_rssi(void)
|
|||
rssi = (int8_t)(REG(RFCORE_XREG_RSSI) & RFCORE_XREG_RSSI_RSSI_VAL) - RSSI_OFFSET;
|
||||
|
||||
/* If we were off, turn back off */
|
||||
if((rf_flags & WAS_OFF) == WAS_OFF) {
|
||||
rf_flags &= ~WAS_OFF;
|
||||
if(was_off) {
|
||||
off();
|
||||
}
|
||||
|
||||
|
@ -345,12 +344,13 @@ static int
|
|||
channel_clear(void)
|
||||
{
|
||||
int cca;
|
||||
uint8_t was_off = 0;
|
||||
|
||||
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;
|
||||
was_off = 1;
|
||||
on();
|
||||
}
|
||||
|
||||
|
@ -364,8 +364,7 @@ channel_clear(void)
|
|||
}
|
||||
|
||||
/* If we were off, turn back off */
|
||||
if((rf_flags & WAS_OFF) == WAS_OFF) {
|
||||
rf_flags &= ~WAS_OFF;
|
||||
if(was_off) {
|
||||
off();
|
||||
}
|
||||
|
||||
|
@ -561,13 +560,14 @@ transmit(unsigned short transmit_len)
|
|||
uint8_t counter;
|
||||
int ret = RADIO_TX_ERR;
|
||||
rtimer_clock_t t0;
|
||||
uint8_t was_off = 0;
|
||||
|
||||
PRINTF("RF: Transmit\n");
|
||||
|
||||
if(!(rf_flags & RX_ACTIVE)) {
|
||||
t0 = RTIMER_NOW();
|
||||
on();
|
||||
rf_flags |= WAS_OFF;
|
||||
was_off = 1;
|
||||
while(RTIMER_CLOCK_LT(RTIMER_NOW(), t0 + ONOFF_TIME));
|
||||
}
|
||||
|
||||
|
@ -609,8 +609,7 @@ transmit(unsigned short transmit_len)
|
|||
ENERGEST_OFF(ENERGEST_TYPE_TRANSMIT);
|
||||
ENERGEST_ON(ENERGEST_TYPE_LISTEN);
|
||||
|
||||
if(rf_flags & WAS_OFF) {
|
||||
rf_flags &= ~WAS_OFF;
|
||||
if(was_off) {
|
||||
off();
|
||||
}
|
||||
|
||||
|
|
72
cpu/cc2538/dev/cc2538-sensors.h
Normal file
72
cpu/cc2538/dev/cc2538-sensors.h
Normal file
|
@ -0,0 +1,72 @@
|
|||
/*
|
||||
* Copyright (c) 2015, Zolertia - http://www.zolertia.com
|
||||
* Copyright (c) 2015, University of Bristol - http://www.bristol.ac.uk
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in the
|
||||
* documentation and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. Neither the name of the 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-sensors CC2538 Built-In Sensors
|
||||
*
|
||||
* Module controlling sensors on the CC2538 SoC (Tmp and VDD3)
|
||||
* @{
|
||||
*
|
||||
* \file
|
||||
* Generic header usable by all CC2538 sensor drivers
|
||||
*/
|
||||
/*---------------------------------------------------------------------------*/
|
||||
#ifndef CC2538_SENSORS_H_
|
||||
#define CC2538_SENSORS_H_
|
||||
/*---------------------------------------------------------------------------*/
|
||||
#include "lib/sensors.h"
|
||||
#include "dev/cc2538-temp-sensor.h"
|
||||
#include "dev/vdd3-sensor.h"
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/**
|
||||
* \name CC2538 sensor constants
|
||||
*
|
||||
* These constants are used by various sensors on the CC2538. They can be used
|
||||
* to differentiate between raw and converted readings, to configure ADC
|
||||
* decimation rate (where applicable).
|
||||
* @{
|
||||
*/
|
||||
#define CC2538_SENSORS_VALUE_TYPE_RAW 0 /**< Request the raw reading */
|
||||
#define CC2538_SENSORS_VALUE_TYPE_CONVERTED 1 /**< Request the converted reading */
|
||||
|
||||
#define CC2538_SENSORS_ERROR 0x80000000 /**< Generic Error */
|
||||
/** @} */
|
||||
/*---------------------------------------------------------------------------*/
|
||||
#endif /* CC2538_SENSORS_H_ */
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
77
cpu/cc2538/dev/cc2538-temp-sensor.c
Normal file
77
cpu/cc2538/dev/cc2538-temp-sensor.c
Normal file
|
@ -0,0 +1,77 @@
|
|||
/*
|
||||
* Copyright (c) 2015, Zolertia - http://www.zolertia.com
|
||||
* Copyright (c) 2015, University of Bristol - http://www.bristol.ac.uk
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in the
|
||||
* documentation and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. Neither the name of the 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-temp-sensor
|
||||
* @{
|
||||
*
|
||||
* \file
|
||||
* Driver for the CC2538 On-Chip temperature sensor
|
||||
*/
|
||||
/*---------------------------------------------------------------------------*/
|
||||
#include "contiki.h"
|
||||
#include "lib/sensors.h"
|
||||
#include "dev/adc.h"
|
||||
#include "dev/cc2538-sensors.h"
|
||||
|
||||
#include <stdint.h>
|
||||
/*---------------------------------------------------------------------------*/
|
||||
static int
|
||||
value(int type)
|
||||
{
|
||||
int raw = adc_get(SOC_ADC_ADCCON_CH_TEMP, SOC_ADC_ADCCON_REF_INT,
|
||||
SOC_ADC_ADCCON_DIV_512);
|
||||
|
||||
if(type == CC2538_SENSORS_VALUE_TYPE_RAW) {
|
||||
return raw;
|
||||
} else if(type == CC2538_SENSORS_VALUE_TYPE_CONVERTED) {
|
||||
return 25000 + ((raw >> 4) - 1422) * 10000 / 42;
|
||||
}
|
||||
|
||||
return CC2538_SENSORS_ERROR;
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
static int
|
||||
configure(int type, int value)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
static int
|
||||
status(int type)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
SENSORS_SENSOR(cc2538_temp_sensor, TEMP_SENSOR, value, configure, status);
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/** @} */
|
71
cpu/cc2538/dev/cc2538-temp-sensor.h
Normal file
71
cpu/cc2538/dev/cc2538-temp-sensor.h
Normal file
|
@ -0,0 +1,71 @@
|
|||
/*
|
||||
* Copyright (c) 2015, Zolertia - http://www.zolertia.com
|
||||
* Copyright (c) 2015, University of Bristol - http://www.bristol.ac.uk
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in the
|
||||
* documentation and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. Neither the name of the 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-sensors
|
||||
* @{
|
||||
*
|
||||
* \defgroup cc2538-temp-sensor CC2538 on-chip temperature Sensor
|
||||
*
|
||||
* Driver for the CC2538 on-chip temperature sensor
|
||||
*
|
||||
* This driver can return the raw as well as the converted value of the sensor
|
||||
* reading. This is controlled by the type argument of the sensor driver's
|
||||
* value() function. The choices for the type argument are:
|
||||
* - CC2538_SENSORS_VALUE_TYPE_RAW (value() returns the raw reading)
|
||||
* - CC2538_SENSORS_VALUE_TYPE_CONVERTED (value() returns degrees mC)
|
||||
* @{
|
||||
*
|
||||
* \file
|
||||
* Header file for the CC2538 on-chip temperature Sensor Driver
|
||||
*/
|
||||
/*---------------------------------------------------------------------------*/
|
||||
#ifndef CC2538_TEMP_SENSOR_H_
|
||||
#define CC2538_TEMP_SENSOR_H_
|
||||
/*---------------------------------------------------------------------------*/
|
||||
#include "lib/sensors.h"
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/**
|
||||
* \name temperature sensor
|
||||
* @{
|
||||
*/
|
||||
#define TEMP_SENSOR "On-Chip Temperature"
|
||||
/** @} */
|
||||
/*---------------------------------------------------------------------------*/
|
||||
extern const struct sensors_sensor cc2538_temp_sensor;
|
||||
/*---------------------------------------------------------------------------*/
|
||||
#endif /* CC2538_TEMP_SENSOR_H_ */
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
|
@ -79,69 +79,41 @@ notify(uint8_t mask, uint8_t port)
|
|||
}
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/** \brief Interrupt service routine for Port A */
|
||||
void
|
||||
gpio_port_a_isr()
|
||||
/** \brief Interrupt service routine for Port \a port
|
||||
* \param port Number between 0 and 3. Port A: 0, Port B: 1, etc.
|
||||
*/
|
||||
static void
|
||||
gpio_port_isr(uint8_t port)
|
||||
{
|
||||
uint32_t base;
|
||||
uint8_t int_status, power_up_int_status;
|
||||
|
||||
lpm_exit();
|
||||
|
||||
ENERGEST_ON(ENERGEST_TYPE_IRQ);
|
||||
|
||||
notify(REG(GPIO_A_BASE | GPIO_MIS), GPIO_A_NUM);
|
||||
base = GPIO_PORT_TO_BASE(port);
|
||||
int_status = GPIO_GET_MASKED_INT_STATUS(base);
|
||||
power_up_int_status = GPIO_GET_POWER_UP_INT_STATUS(port);
|
||||
|
||||
GPIO_CLEAR_INTERRUPT(GPIO_A_BASE, 0xFF);
|
||||
GPIO_CLEAR_POWER_UP_INTERRUPT(GPIO_A_NUM, 0xFF);
|
||||
notify(int_status | power_up_int_status, port);
|
||||
|
||||
GPIO_CLEAR_INTERRUPT(base, int_status);
|
||||
GPIO_CLEAR_POWER_UP_INTERRUPT(port, power_up_int_status);
|
||||
|
||||
ENERGEST_OFF(ENERGEST_TYPE_IRQ);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/** \brief Interrupt service routine for Port B */
|
||||
void
|
||||
gpio_port_b_isr()
|
||||
{
|
||||
lpm_exit();
|
||||
|
||||
ENERGEST_ON(ENERGEST_TYPE_IRQ);
|
||||
|
||||
notify(REG(GPIO_B_BASE | GPIO_MIS), GPIO_B_NUM);
|
||||
|
||||
GPIO_CLEAR_INTERRUPT(GPIO_B_BASE, 0xFF);
|
||||
GPIO_CLEAR_POWER_UP_INTERRUPT(GPIO_B_NUM, 0xFF);
|
||||
|
||||
ENERGEST_OFF(ENERGEST_TYPE_IRQ);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/** \brief Interrupt service routine for Port C */
|
||||
void
|
||||
gpio_port_c_isr()
|
||||
{
|
||||
lpm_exit();
|
||||
|
||||
ENERGEST_ON(ENERGEST_TYPE_IRQ);
|
||||
|
||||
notify(REG(GPIO_C_BASE | GPIO_MIS), GPIO_C_NUM);
|
||||
|
||||
GPIO_CLEAR_INTERRUPT(GPIO_C_BASE, 0xFF);
|
||||
GPIO_CLEAR_POWER_UP_INTERRUPT(GPIO_C_NUM, 0xFF);
|
||||
|
||||
ENERGEST_OFF(ENERGEST_TYPE_IRQ);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/** \brief Interrupt service routine for Port D */
|
||||
void
|
||||
gpio_port_d_isr()
|
||||
{
|
||||
lpm_exit();
|
||||
|
||||
ENERGEST_ON(ENERGEST_TYPE_IRQ);
|
||||
|
||||
notify(REG(GPIO_D_BASE | GPIO_MIS), GPIO_D_NUM);
|
||||
|
||||
GPIO_CLEAR_INTERRUPT(GPIO_D_BASE, 0xFF);
|
||||
GPIO_CLEAR_POWER_UP_INTERRUPT(GPIO_D_NUM, 0xFF);
|
||||
|
||||
ENERGEST_OFF(ENERGEST_TYPE_IRQ);
|
||||
#define GPIO_PORT_ISR(lowercase_port, uppercase_port) \
|
||||
void \
|
||||
gpio_port_##lowercase_port##_isr(void) \
|
||||
{ \
|
||||
gpio_port_isr(GPIO_##uppercase_port##_NUM); \
|
||||
}
|
||||
GPIO_PORT_ISR(a, A)
|
||||
GPIO_PORT_ISR(b, B)
|
||||
GPIO_PORT_ISR(c, C)
|
||||
GPIO_PORT_ISR(d, D)
|
||||
/*---------------------------------------------------------------------------*/
|
||||
void
|
||||
gpio_init()
|
||||
|
|
|
@ -91,28 +91,28 @@ typedef void (* gpio_callback_t)(uint8_t port, uint8_t pin);
|
|||
* \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)
|
||||
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)
|
||||
do { REG((PORT_BASE) + GPIO_DIR) |= (PIN_MASK); } while(0)
|
||||
|
||||
/** \brief Set pins with PIN_MASK of port with PORT_BASE high.
|
||||
* \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_PIN(PORT_BASE, PIN_MASK) \
|
||||
do { REG(((PORT_BASE) | GPIO_DATA) + ((PIN_MASK) << 2)) = 0xFF; } while(0)
|
||||
do { REG((PORT_BASE) + GPIO_DATA + ((PIN_MASK) << 2)) = 0xFF; } while(0)
|
||||
|
||||
/** \brief Set pins with PIN_MASK of port with PORT_BASE low.
|
||||
* \param PORT_BASE GPIO Port register offset
|
||||
* \param PIN_MASK Pin number mask. Pin 0: 0x01, Pin 1: 0x02 ... Pin 7: 0x80
|
||||
*/
|
||||
#define GPIO_CLR_PIN(PORT_BASE, PIN_MASK) \
|
||||
do { REG(((PORT_BASE) | GPIO_DATA) + ((PIN_MASK) << 2)) = 0x00; } while(0)
|
||||
do { REG((PORT_BASE) + GPIO_DATA + ((PIN_MASK) << 2)) = 0x00; } while(0)
|
||||
|
||||
/** \brief Set pins with PIN_MASK of port with PORT_BASE to value.
|
||||
* \param PORT_BASE GPIO Port register offset
|
||||
|
@ -133,7 +133,7 @@ typedef void (* gpio_callback_t)(uint8_t port, uint8_t pin);
|
|||
* and then use 0x0A as the value ((1 << 3) | (1 << 1) for pins 3 and 1)
|
||||
*/
|
||||
#define GPIO_WRITE_PIN(PORT_BASE, PIN_MASK, value) \
|
||||
do { REG(((PORT_BASE) | GPIO_DATA) + ((PIN_MASK) << 2)) = (value); } while(0)
|
||||
do { REG((PORT_BASE) + GPIO_DATA + ((PIN_MASK) << 2)) = (value); } while(0)
|
||||
|
||||
/** \brief Read pins with PIN_MASK of port with PORT_BASE.
|
||||
* \param PORT_BASE GPIO Port register offset
|
||||
|
@ -146,21 +146,21 @@ typedef void (* gpio_callback_t)(uint8_t port, uint8_t pin);
|
|||
* the macro will return 0x81.
|
||||
*/
|
||||
#define GPIO_READ_PIN(PORT_BASE, PIN_MASK) \
|
||||
REG(((PORT_BASE) | GPIO_DATA) + ((PIN_MASK) << 2))
|
||||
REG((PORT_BASE) + GPIO_DATA + ((PIN_MASK) << 2))
|
||||
|
||||
/** \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)
|
||||
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)
|
||||
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.
|
||||
|
@ -168,7 +168,7 @@ typedef void (* gpio_callback_t)(uint8_t port, uint8_t pin);
|
|||
* \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)
|
||||
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).
|
||||
|
@ -176,7 +176,7 @@ typedef void (* gpio_callback_t)(uint8_t port, uint8_t pin);
|
|||
* \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)
|
||||
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.
|
||||
|
@ -184,7 +184,7 @@ typedef void (* gpio_callback_t)(uint8_t port, uint8_t pin);
|
|||
* \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)
|
||||
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.
|
||||
|
@ -192,7 +192,7 @@ typedef void (* gpio_callback_t)(uint8_t port, uint8_t pin);
|
|||
* \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)
|
||||
do { REG((PORT_BASE) + GPIO_IEV) &= ~(PIN_MASK); } while(0)
|
||||
|
||||
/** \brief Enable interrupt triggering for pins with PIN_MASK of port with
|
||||
* PORT_BASE.
|
||||
|
@ -200,7 +200,7 @@ typedef void (* gpio_callback_t)(uint8_t port, uint8_t pin);
|
|||
* \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)
|
||||
do { REG((PORT_BASE) + GPIO_IE) |= (PIN_MASK); } while(0)
|
||||
|
||||
/** \brief Disable interrupt triggering for pins with PIN_MASK of port with
|
||||
* PORT_BASE.
|
||||
|
@ -208,7 +208,32 @@ typedef void (* gpio_callback_t)(uint8_t port, uint8_t pin);
|
|||
* \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)
|
||||
do { REG((PORT_BASE) + GPIO_IE) &= ~(PIN_MASK); } while(0)
|
||||
|
||||
/** \brief Get raw interrupt status of port with PORT_BASE.
|
||||
* \param PORT_BASE GPIO Port register offset
|
||||
* \return Bit-mask reflecting the raw interrupt status of all the port pins
|
||||
*
|
||||
* The bits set in the returned bit-mask reflect the status of the interrupts
|
||||
* trigger conditions detected (raw, before interrupt masking), indicating that
|
||||
* all the requirements are met, before they are finally allowed to trigger by
|
||||
* the interrupt mask. The bits cleared indicate that corresponding input pins
|
||||
* have not initiated an interrupt.
|
||||
*/
|
||||
#define GPIO_GET_RAW_INT_STATUS(PORT_BASE) \
|
||||
REG((PORT_BASE) + GPIO_RIS)
|
||||
|
||||
/** \brief Get masked interrupt status of port with PORT_BASE.
|
||||
* \param PORT_BASE GPIO Port register offset
|
||||
* \return Bit-mask reflecting the masked interrupt status of all the port pins
|
||||
*
|
||||
* The bits set in the returned bit-mask reflect the status of input lines
|
||||
* triggering an interrupt. The bits cleared indicate that either no interrupt
|
||||
* has been generated, or the interrupt is masked. This is the state of the
|
||||
* interrupt after interrupt masking.
|
||||
*/
|
||||
#define GPIO_GET_MASKED_INT_STATUS(PORT_BASE) \
|
||||
REG((PORT_BASE) + GPIO_MIS)
|
||||
|
||||
/** \brief Clear interrupt triggering for pins with PIN_MASK of port with
|
||||
* PORT_BASE.
|
||||
|
@ -216,7 +241,7 @@ typedef void (* gpio_callback_t)(uint8_t port, uint8_t pin);
|
|||
* \param PIN_MASK Pin number mask. Pin 0: 0x01, Pin 1: 0x02 ... Pin 7: 0x80
|
||||
*/
|
||||
#define GPIO_CLEAR_INTERRUPT(PORT_BASE, PIN_MASK) \
|
||||
do { REG((PORT_BASE) | GPIO_IC) = (PIN_MASK); } while(0)
|
||||
do { REG((PORT_BASE) + GPIO_IC) = (PIN_MASK); } while(0)
|
||||
|
||||
/** \brief Configure the pin to be under peripheral control with PIN_MASK of
|
||||
* port with PORT_BASE.
|
||||
|
@ -224,7 +249,7 @@ typedef void (* gpio_callback_t)(uint8_t port, uint8_t pin);
|
|||
* \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)
|
||||
do { REG((PORT_BASE) + GPIO_AFSEL) |= (PIN_MASK); } while(0)
|
||||
|
||||
/** \brief Configure the pin to be software controlled with PIN_MASK of port
|
||||
* with PORT_BASE.
|
||||
|
@ -232,7 +257,7 @@ typedef void (* gpio_callback_t)(uint8_t port, uint8_t pin);
|
|||
* \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)
|
||||
do { REG((PORT_BASE) + GPIO_AFSEL) &= ~(PIN_MASK); } while(0)
|
||||
|
||||
/** \brief Set pins with PIN_MASK of port PORT to trigger a power-up interrupt
|
||||
* on rising edge.
|
||||
|
@ -240,7 +265,7 @@ typedef void (* gpio_callback_t)(uint8_t port, uint8_t pin);
|
|||
* \param PIN_MASK Pin number mask. Pin 0: 0x01, Pin 1: 0x02 ... Pin 7: 0x80
|
||||
*/
|
||||
#define GPIO_POWER_UP_ON_RISING(PORT, PIN_MASK) \
|
||||
do { REG(GPIO_PORT_TO_BASE(PORT) | GPIO_P_EDGE_CTRL) &= \
|
||||
do { REG(GPIO_PORT_TO_BASE(PORT) + GPIO_P_EDGE_CTRL) &= \
|
||||
~((PIN_MASK) << ((PORT) << 3)); } while(0)
|
||||
|
||||
/** \brief Set pins with PIN_MASK of port PORT to trigger a power-up interrupt
|
||||
|
@ -249,7 +274,7 @@ typedef void (* gpio_callback_t)(uint8_t port, uint8_t pin);
|
|||
* \param PIN_MASK Pin number mask. Pin 0: 0x01, Pin 1: 0x02 ... Pin 7: 0x80
|
||||
*/
|
||||
#define GPIO_POWER_UP_ON_FALLING(PORT, PIN_MASK) \
|
||||
do { REG(GPIO_PORT_TO_BASE(PORT) | GPIO_P_EDGE_CTRL) |= \
|
||||
do { REG(GPIO_PORT_TO_BASE(PORT) + GPIO_P_EDGE_CTRL) |= \
|
||||
(PIN_MASK) << ((PORT) << 3); } while(0)
|
||||
|
||||
/** \brief Enable power-up interrupt triggering for pins with PIN_MASK of port
|
||||
|
@ -258,7 +283,7 @@ typedef void (* gpio_callback_t)(uint8_t port, uint8_t pin);
|
|||
* \param PIN_MASK Pin number mask. Pin 0: 0x01, Pin 1: 0x02 ... Pin 7: 0x80
|
||||
*/
|
||||
#define GPIO_ENABLE_POWER_UP_INTERRUPT(PORT, PIN_MASK) \
|
||||
do { REG(GPIO_PORT_TO_BASE(PORT) | GPIO_PI_IEN) |= \
|
||||
do { REG(GPIO_PORT_TO_BASE(PORT) + GPIO_PI_IEN) |= \
|
||||
(PIN_MASK) << ((PORT) << 3); } while(0)
|
||||
|
||||
/** \brief Disable power-up interrupt triggering for pins with PIN_MASK of port
|
||||
|
@ -267,16 +292,24 @@ typedef void (* gpio_callback_t)(uint8_t port, uint8_t pin);
|
|||
* \param PIN_MASK Pin number mask. Pin 0: 0x01, Pin 1: 0x02 ... Pin 7: 0x80
|
||||
*/
|
||||
#define GPIO_DISABLE_POWER_UP_INTERRUPT(PORT, PIN_MASK) \
|
||||
do { REG(GPIO_PORT_TO_BASE(PORT) | GPIO_PI_IEN) &= \
|
||||
do { REG(GPIO_PORT_TO_BASE(PORT) + GPIO_PI_IEN) &= \
|
||||
~((PIN_MASK) << ((PORT) << 3)); } while(0)
|
||||
|
||||
/** \brief Get power-up interrupt status of port PORT.
|
||||
* \param PORT GPIO Port (not port base address)
|
||||
* \return Bit-mask reflecting the power-up interrupt status of all the port
|
||||
* pins
|
||||
*/
|
||||
#define GPIO_GET_POWER_UP_INT_STATUS(PORT) \
|
||||
((REG(GPIO_PORT_TO_BASE(PORT) + GPIO_IRQ_DETECT_ACK) >> ((PORT) << 3)) & 0xFF)
|
||||
|
||||
/** \brief Clear power-up interrupt triggering for pins with PIN_MASK of port
|
||||
* PORT.
|
||||
* \param PORT GPIO Port (not port base address)
|
||||
* \param PIN_MASK Pin number mask. Pin 0: 0x01, Pin 1: 0x02 ... Pin 7: 0x80
|
||||
*/
|
||||
#define GPIO_CLEAR_POWER_UP_INTERRUPT(PORT, PIN_MASK) \
|
||||
do { REG(GPIO_PORT_TO_BASE(PORT) | GPIO_IRQ_DETECT_ACK) = \
|
||||
do { REG(GPIO_PORT_TO_BASE(PORT) + GPIO_IRQ_DETECT_ACK) = \
|
||||
(PIN_MASK) << ((PORT) << 3); } while(0)
|
||||
|
||||
/**
|
||||
|
|
254
cpu/cc2538/dev/i2c.c
Normal file
254
cpu/cc2538/dev/i2c.c
Normal file
|
@ -0,0 +1,254 @@
|
|||
/*
|
||||
* Copyright (c) 2015, Mehdi Migault
|
||||
* 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-i2c cc2538 I2C Control
|
||||
* @{
|
||||
*
|
||||
* \file
|
||||
* Implementation file of the I2C Control module
|
||||
*
|
||||
* \author
|
||||
* Mehdi Migault
|
||||
*/
|
||||
|
||||
#include "i2c.h"
|
||||
|
||||
#include <stdint.h>
|
||||
#include "clock.h"
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* Additional functions */
|
||||
static uint32_t
|
||||
get_sys_clock(void)
|
||||
{
|
||||
/* Get the clock status diviser */
|
||||
return SYS_CTRL_32MHZ /
|
||||
(1 << (REG(SYS_CTRL_CLOCK_STA) & SYS_CTRL_CLOCK_STA_SYS_DIV));
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
void
|
||||
i2c_init(uint8_t port_sda, uint8_t pin_sda, uint8_t port_scl, uint8_t pin_scl,
|
||||
uint32_t bus_speed)
|
||||
{
|
||||
/* Enable I2C clock in different modes */
|
||||
REG(SYS_CTRL_RCGCI2C) |= 1; /* Run mode */
|
||||
|
||||
/* Reset I2C peripheral */
|
||||
REG(SYS_CTRL_SRI2C) |= 1; /* Reset position */
|
||||
|
||||
/* Delay for a little bit */
|
||||
clock_delay_usec(50);
|
||||
|
||||
REG(SYS_CTRL_SRI2C) &= ~1; /* Normal position */
|
||||
|
||||
/* Set pins in input */
|
||||
GPIO_SET_INPUT(GPIO_PORT_TO_BASE(port_sda), GPIO_PIN_MASK(pin_sda));
|
||||
GPIO_SET_INPUT(GPIO_PORT_TO_BASE(port_scl), GPIO_PIN_MASK(pin_scl));
|
||||
|
||||
/* Set peripheral control for the pins */
|
||||
GPIO_PERIPHERAL_CONTROL(GPIO_PORT_TO_BASE(port_sda), GPIO_PIN_MASK(pin_sda));
|
||||
GPIO_PERIPHERAL_CONTROL(GPIO_PORT_TO_BASE(port_scl), GPIO_PIN_MASK(pin_scl));
|
||||
|
||||
/* Set the pad to no drive type */
|
||||
ioc_set_over(port_sda, pin_sda, IOC_OVERRIDE_DIS);
|
||||
ioc_set_over(port_scl, pin_scl, IOC_OVERRIDE_DIS);
|
||||
|
||||
/* Set pins as peripheral inputs */
|
||||
REG(IOC_I2CMSSDA) = ioc_input_sel(port_sda, pin_sda);
|
||||
REG(IOC_I2CMSSCL) = ioc_input_sel(port_scl, pin_scl);
|
||||
|
||||
/* Set pins as peripheral outputs */
|
||||
ioc_set_sel(port_sda, pin_sda, IOC_PXX_SEL_I2C_CMSSDA);
|
||||
ioc_set_sel(port_scl, pin_scl, IOC_PXX_SEL_I2C_CMSSCL);
|
||||
|
||||
/* Enable the I2C master module */
|
||||
i2c_master_enable();
|
||||
|
||||
/* t the master clock frequency */
|
||||
i2c_set_frequency(bus_speed);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
void
|
||||
i2c_master_enable(void)
|
||||
{
|
||||
REG(I2CM_CR) |= 0x10; /* Set MFE bit */
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
void
|
||||
i2c_master_disable(void)
|
||||
{
|
||||
REG(I2CM_CR) &= ~0x10; /* Reset MFE bit */
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
void
|
||||
i2c_set_frequency(uint32_t freq)
|
||||
{
|
||||
/* Peripheral clock setting, using the system clock */
|
||||
REG(I2CM_TPR) = ((get_sys_clock() + (2 * 10 * freq) - 1) /
|
||||
(2 * 10 * freq)) - 1;
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
void
|
||||
i2c_master_set_slave_address(uint8_t slave_addr, uint8_t access_mode)
|
||||
{
|
||||
if(access_mode) {
|
||||
REG(I2CM_SA) = ((slave_addr << 1) | 1);
|
||||
} else {
|
||||
REG(I2CM_SA) = (slave_addr << 1);
|
||||
}
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
void
|
||||
i2c_master_data_put(uint8_t data)
|
||||
{
|
||||
REG(I2CM_DR) = data;
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
uint8_t
|
||||
i2c_master_data_get(void)
|
||||
{
|
||||
return REG(I2CM_DR);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
void
|
||||
i2c_master_command(uint8_t cmd)
|
||||
{
|
||||
REG(I2CM_CTRL) = cmd;
|
||||
/* Here we need a delay, otherwise the I2C module keep the receiver mode */
|
||||
clock_delay_usec(1);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
uint8_t
|
||||
i2c_master_busy(void)
|
||||
{
|
||||
return REG(I2CM_STAT) & I2CM_STAT_BUSY;
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
uint8_t
|
||||
i2c_master_error(void)
|
||||
{
|
||||
uint8_t temp = REG(I2CM_STAT); /* Get all status */
|
||||
if(temp & I2CM_STAT_BUSY) { /* No valid if BUSY bit is set */
|
||||
return I2C_MASTER_ERR_NONE;
|
||||
} else if(temp & (I2CM_STAT_ERROR | I2CM_STAT_ARBLST)) {
|
||||
return temp; /* Compare later */
|
||||
}
|
||||
return I2C_MASTER_ERR_NONE;
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
uint8_t
|
||||
i2c_single_send(uint8_t slave_addr, uint8_t data)
|
||||
{
|
||||
i2c_master_set_slave_address(slave_addr, I2C_SEND);
|
||||
i2c_master_data_put(data);
|
||||
i2c_master_command(I2C_MASTER_CMD_SINGLE_SEND);
|
||||
|
||||
while(i2c_master_busy());
|
||||
|
||||
/* Return the STAT register of I2C module if error occured, I2C_MASTER_ERR_NONE otherwise */
|
||||
return i2c_master_error();
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
uint8_t
|
||||
i2c_single_receive(uint8_t slave_addr, uint8_t *data)
|
||||
{
|
||||
uint32_t temp;
|
||||
|
||||
i2c_master_set_slave_address(slave_addr, I2C_RECEIVE);
|
||||
i2c_master_command(I2C_MASTER_CMD_SINGLE_RECEIVE);
|
||||
|
||||
while(i2c_master_busy());
|
||||
temp = i2c_master_error();
|
||||
if(temp == I2C_MASTER_ERR_NONE) {
|
||||
*data = i2c_master_data_get();
|
||||
}
|
||||
return temp;
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
uint8_t
|
||||
i2c_burst_send(uint8_t slave_addr, uint8_t *data, uint8_t len)
|
||||
{
|
||||
uint8_t sent;
|
||||
if((len == 0) || (data == NULL)) {
|
||||
return I2CM_STAT_INVALID;
|
||||
}
|
||||
if(len == 1) {
|
||||
return i2c_single_send(slave_addr, data[0]);
|
||||
}
|
||||
i2c_master_set_slave_address(slave_addr, I2C_SEND);
|
||||
i2c_master_data_put(data[0]);
|
||||
i2c_master_command(I2C_MASTER_CMD_BURST_SEND_START);
|
||||
while(i2c_master_busy());
|
||||
if(i2c_master_error() == I2C_MASTER_ERR_NONE) {
|
||||
for(sent = 1; sent <= (len - 2); sent++) {
|
||||
i2c_master_data_put(data[sent]);
|
||||
i2c_master_command(I2C_MASTER_CMD_BURST_SEND_CONT);
|
||||
while(i2c_master_busy());
|
||||
}
|
||||
/* This should be the last byte, stop sending */
|
||||
i2c_master_data_put(data[len - 1]);
|
||||
i2c_master_command(I2C_MASTER_CMD_BURST_SEND_FINISH);
|
||||
while(i2c_master_busy());
|
||||
}
|
||||
|
||||
/* Return the STAT register of I2C module if error occurred, I2C_MASTER_ERR_NONE otherwise */
|
||||
return i2c_master_error();
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
uint8_t
|
||||
i2c_burst_receive(uint8_t slave_addr, uint8_t *data, uint8_t len)
|
||||
{
|
||||
uint8_t recv = 0;
|
||||
if((len == 0) || data == NULL) {
|
||||
return I2CM_STAT_INVALID;
|
||||
}
|
||||
if(len == 1) {
|
||||
return i2c_single_receive(slave_addr, &data[0]);
|
||||
}
|
||||
i2c_master_set_slave_address(slave_addr, I2C_RECEIVE);
|
||||
i2c_master_command(I2C_MASTER_CMD_BURST_RECEIVE_START);
|
||||
while(i2c_master_busy());
|
||||
if(i2c_master_error() == I2C_MASTER_ERR_NONE) {
|
||||
data[0] = i2c_master_data_get();
|
||||
/* If we got 2 or more bytes pending to be received, keep going*/
|
||||
for(recv = 1; recv <= (len - 2); recv++) {
|
||||
i2c_master_command(I2C_MASTER_CMD_BURST_RECEIVE_CONT);
|
||||
while(i2c_master_busy());
|
||||
data[recv] = i2c_master_data_get();
|
||||
}
|
||||
/* This should be the last byte, stop receiving */
|
||||
i2c_master_command(I2C_MASTER_CMD_BURST_RECEIVE_FINISH);
|
||||
while(i2c_master_busy());
|
||||
data[len - 1] = i2c_master_data_get();
|
||||
}
|
||||
return i2c_master_error();
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/** @} */
|
240
cpu/cc2538/dev/i2c.h
Normal file
240
cpu/cc2538/dev/i2c.h
Normal file
|
@ -0,0 +1,240 @@
|
|||
/*
|
||||
* Copyright (c) 2015, Mehdi Migault
|
||||
* 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-i2c cc2538 I2C Control
|
||||
*
|
||||
* cc2538 I2C Control Module
|
||||
* @{
|
||||
*
|
||||
* \file
|
||||
* Header file with declarations for the I2C Control module
|
||||
*
|
||||
* \author
|
||||
* Mehdi Migault
|
||||
*/
|
||||
#ifndef I2C_H_
|
||||
#define I2C_H_
|
||||
|
||||
#include "reg.h"
|
||||
#include "sys-ctrl.h"
|
||||
#include "gpio.h"
|
||||
#include "ioc.h"
|
||||
#include <stdio.h> /* For debug */
|
||||
#include "clock.h" /* For temporisation */
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/** \name I2C Master commands
|
||||
* @{
|
||||
*/
|
||||
#define I2C_MASTER_CMD_SINGLE_SEND 0x00000007
|
||||
#define I2C_MASTER_CMD_SINGLE_RECEIVE 0x00000007
|
||||
#define I2C_MASTER_CMD_BURST_SEND_START 0x00000003
|
||||
#define I2C_MASTER_CMD_BURST_SEND_CONT 0x00000001
|
||||
#define I2C_MASTER_CMD_BURST_SEND_FINISH 0x00000005
|
||||
#define I2C_MASTER_CMD_BURST_SEND_ERROR_STOP 0x00000004
|
||||
#define I2C_MASTER_CMD_BURST_RECEIVE_START 0x0000000b
|
||||
#define I2C_MASTER_CMD_BURST_RECEIVE_CONT 0x00000009
|
||||
#define I2C_MASTER_CMD_BURST_RECEIVE_FINISH 0x00000005
|
||||
#define I2C_MASTER_CMD_BURST_RECEIVE_ERROR_STOP 0x00000004
|
||||
/** @} */
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/** \name I2C Master status flags
|
||||
* @{
|
||||
*/
|
||||
#define I2C_MASTER_ERR_NONE 0
|
||||
#define I2CM_STAT_BUSY 0x00000001
|
||||
#define I2CM_STAT_ERROR 0x00000002
|
||||
#define I2CM_STAT_ADRACK 0x00000004
|
||||
#define I2CM_STAT_DATACK 0x00000008
|
||||
#define I2CM_STAT_ARBLST 0x00000010
|
||||
#define I2CM_STAT_IDLE 0x00000020
|
||||
#define I2CM_STAT_BUSBSY 0x00000040
|
||||
#define I2CM_STAT_INVALID 0x00000080
|
||||
/** @} */
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/** \name I2C registers
|
||||
* @{
|
||||
*/
|
||||
#define I2CM_CR 0x40020020 /* I2C master config */
|
||||
#define I2CM_TPR 0x4002000C /* I2C master timer period */
|
||||
#define I2CM_SA 0x40020000 /* I2C master slave address */
|
||||
#define I2CM_DR 0x40020008 /* I2C master data */
|
||||
#define I2CM_CTRL 0x40020004 /* Master control in write */
|
||||
#define I2CM_STAT I2CM_CTRL /* Master status in read */
|
||||
/** @} */
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/** \name I2C Miscellaneous
|
||||
* @{
|
||||
*/
|
||||
#define I2C_SCL_NORMAL_BUS_SPEED 100000 /* 100KHz I2C */
|
||||
#define I2C_SCL_FAST_BUS_SPEED 400000 /* 400KHz I2C */
|
||||
#define I2C_RECEIVE 0x01 /* Master receive */
|
||||
#define I2C_SEND 0x00 /* Master send */
|
||||
/** @} */
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/**
|
||||
* \name I2C Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* \brief Initialize the I2C peripheral and pins
|
||||
* \param port_sda The GPIO number of the pin used fort SDA
|
||||
* \param pin_sda The pin number used for SDA
|
||||
* \param port_scl The GPIO number of the pin used fort SCL
|
||||
* \param pin_scl The pin number used for SCL
|
||||
* \param bus_speed The clock frequency used by I2C module
|
||||
*
|
||||
* \e bus_speed can take the following values:
|
||||
*
|
||||
* - I2C_SCL_NORMAL_BUS_SPEED : 100KHz
|
||||
* - I2C_SCL_FAST_BUS_SPEED : 400KHz
|
||||
*/
|
||||
void i2c_init(uint8_t port_sda, uint8_t pin_sda, uint8_t port_scl,
|
||||
uint8_t pin_scl, uint32_t bus_speed);
|
||||
|
||||
/** \brief Enable master I2C module */
|
||||
void i2c_master_enable(void);
|
||||
|
||||
/** \brief Disable master I2C module */
|
||||
void i2c_master_disable(void);
|
||||
|
||||
/**
|
||||
* \brief Initialize I2C peripheral clock with given frequency
|
||||
* \param freq The desired frequency
|
||||
*
|
||||
* \e freq can take the following values:
|
||||
*
|
||||
* - I2C_SCL_NORMAL_BUS_SPEED : 100KHz
|
||||
* - I2C_SCL_FAST_BUS_SPEED : 400KHz
|
||||
*/
|
||||
void i2c_set_frequency(uint32_t freq);
|
||||
|
||||
/**
|
||||
* \brief Set the address of slave and access mode for the next I2C communication
|
||||
* \param slave_addr The receiver slave address on 7 bits
|
||||
* \param access_mode The I2C access mode (send/receive)
|
||||
*
|
||||
* \e access_mode can take the following values:
|
||||
*
|
||||
* - I2C_RECEIVE : 1
|
||||
* - I2C_SEND : 0
|
||||
*/
|
||||
void i2c_master_set_slave_address(uint8_t slave_addr, uint8_t access_mode);
|
||||
|
||||
/**
|
||||
* \brief Prepare data to be transmitted
|
||||
* \param data The byte of data to be transmitted from the I2C master
|
||||
*/
|
||||
void i2c_master_data_put(uint8_t data);
|
||||
|
||||
/**
|
||||
* \brief Return received data from I2C
|
||||
* \return The byte received by I2C after à receive command
|
||||
*/
|
||||
uint8_t i2c_master_data_get(void);
|
||||
|
||||
/**
|
||||
* \brief Control the state of the master module for send and receive operations
|
||||
* \param cmd The operation to perform
|
||||
*
|
||||
* \e cmd can take the following values:
|
||||
*
|
||||
* - I2C_MASTER_CMD_SINGLE_SEND
|
||||
* - I2C_MASTER_CMD_SINGLE_RECEIVE
|
||||
* - I2C_MASTER_CMD_BURST_SEND_START
|
||||
* - I2C_MASTER_CMD_BURST_SEND_CONT
|
||||
* - I2C_MASTER_CMD_BURST_SEND_FINISH
|
||||
* - I2C_MASTER_CMD_BURST_SEND_ERROR_STOP
|
||||
* - I2C_MASTER_CMD_BURST_RECEIVE_START
|
||||
* - I2C_MASTER_CMD_BURST_RECEIVE_CONT
|
||||
* - I2C_MASTER_CMD_BURST_RECEIVE_FINISH
|
||||
* - I2C_MASTER_CMD_BURST_RECEIVE_ERROR_STOP
|
||||
*/
|
||||
void i2c_master_command(uint8_t cmd);
|
||||
|
||||
/**
|
||||
* \brief Return the busy state of I2C module
|
||||
* \retval 0 The I2C module is not busy
|
||||
* \retval 1 The I2C module is busy
|
||||
*/
|
||||
uint8_t i2c_master_busy(void);
|
||||
|
||||
/**
|
||||
* \brief Return the status register if error occurred during last communication
|
||||
* \retval I2C_MASTER_ERR_NONE Return 0 if no error occurred
|
||||
*
|
||||
* If an error occurred, return the status register of the I2C module.
|
||||
* Use the result with the I2CM_STAT_* flags to custom your processing
|
||||
*/
|
||||
uint8_t i2c_master_error(void);
|
||||
/**
|
||||
* \brief Perform all operations to send a byte to a slave
|
||||
* \param slave_addr The adress of the slave to which data are sent
|
||||
* \param data The data to send to the slave
|
||||
* \return Return the value of i2c_master_error() after the I2C operation
|
||||
*/
|
||||
uint8_t i2c_single_send(uint8_t slave_addr, uint8_t data);
|
||||
|
||||
/**
|
||||
* \brief Perform all operations to receive a byte from a slave
|
||||
* \param slave_addr The address of the slave from which data are received
|
||||
* \param data A pointer to store the received data
|
||||
* \return Return the value of i2c_master_error() after the I2C operation
|
||||
*/
|
||||
uint8_t i2c_single_receive(uint8_t slave_addr, uint8_t *data);
|
||||
/**
|
||||
* \brief Perform all operations to send multiple bytes to a slave
|
||||
* \param slave_addr The address of the slave to which data are sent
|
||||
* \param data A pointer to the data to send to the slave
|
||||
* \param len Number of bytes to send
|
||||
* \return Return the value of i2c_master_error() after the I2C operation
|
||||
*/
|
||||
uint8_t i2c_burst_send(uint8_t slave_addr, uint8_t *data, uint8_t len);
|
||||
|
||||
/**
|
||||
* \brief Perform all operations to receive multiple bytes from a slave
|
||||
* \param slave_addr The address of the slave from which data are received
|
||||
* \param data A pointer to store the received data
|
||||
* \param len Number of bytes to receive
|
||||
* \return Return the value of i2c_master_error() after the I2C operation
|
||||
*/
|
||||
uint8_t i2c_burst_receive(uint8_t slave_addr, uint8_t *data, uint8_t len);
|
||||
/** @} */
|
||||
|
||||
#endif /* I2C_H_ */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
|
@ -57,7 +57,7 @@ nvic_init()
|
|||
interrupt_unpend = (uint32_t *)NVIC_UNPEND0;
|
||||
|
||||
/* Provide our interrupt table to the NVIC */
|
||||
REG(SCB_VTABLE) = (NVIC_CONF_VTABLE_BASE | NVIC_CONF_VTABLE_OFFSET);
|
||||
REG(SCB_VTABLE) = (NVIC_CONF_VTABLE_BASE + NVIC_CONF_VTABLE_OFFSET);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
void
|
||||
|
|
|
@ -206,22 +206,22 @@ reset(uint32_t uart_base)
|
|||
uint32_t lchr;
|
||||
|
||||
/* Make sure the UART is disabled before trying to configure it */
|
||||
REG(uart_base | UART_CTL) = UART_CTL_VALUE;
|
||||
REG(uart_base + UART_CTL) = UART_CTL_VALUE;
|
||||
|
||||
/* Clear error status */
|
||||
REG(uart_base | UART_ECR) = 0xFF;
|
||||
REG(uart_base + UART_ECR) = 0xFF;
|
||||
|
||||
/* Store LCHR configuration */
|
||||
lchr = REG(uart_base | UART_LCRH);
|
||||
lchr = REG(uart_base + UART_LCRH);
|
||||
|
||||
/* Flush FIFOs by clearing LCHR.FEN */
|
||||
REG(uart_base | UART_LCRH) = 0;
|
||||
REG(uart_base + UART_LCRH) = 0;
|
||||
|
||||
/* Restore LCHR configuration */
|
||||
REG(uart_base | UART_LCRH) = lchr;
|
||||
REG(uart_base + UART_LCRH) = lchr;
|
||||
|
||||
/* UART Enable */
|
||||
REG(uart_base | UART_CTL) |= UART_CTL_UARTEN;
|
||||
REG(uart_base + UART_CTL) |= UART_CTL_UARTEN;
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
static bool
|
||||
|
@ -232,7 +232,7 @@ permit_pm1(void)
|
|||
for(regs = &uart_regs[0]; regs < &uart_regs[UART_INSTANCE_COUNT]; regs++) {
|
||||
/* Note: UART_FR.TXFE reads 0 if the UART clock is gated. */
|
||||
if((REG(SYS_CTRL_RCGCUART) & regs->sys_ctrl_rcgcuart_uart) != 0 &&
|
||||
(REG(regs->base | UART_FR) & UART_FR_TXFE) == 0) {
|
||||
(REG(regs->base + UART_FR) & UART_FR_TXFE) == 0) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
@ -261,7 +261,7 @@ uart_init(uint8_t uart)
|
|||
REG(SYS_CTRL_DCGCUART) |= regs->sys_ctrl_dcgcuart_uart;
|
||||
|
||||
/* Run on SYS_DIV */
|
||||
REG(regs->base | UART_CC) = 0;
|
||||
REG(regs->base + UART_CC) = 0;
|
||||
|
||||
/*
|
||||
* Select the UARTx RX pin by writing to the IOC_UARTRXD_UARTn register
|
||||
|
@ -292,21 +292,21 @@ uart_init(uint8_t uart)
|
|||
* Acknowledge RX and RX Timeout
|
||||
* Acknowledge Framing, Overrun and Break Errors
|
||||
*/
|
||||
REG(regs->base | UART_IM) = UART_IM_RXIM | UART_IM_RTIM;
|
||||
REG(regs->base | UART_IM) |= UART_IM_OEIM | UART_IM_BEIM | UART_IM_FEIM;
|
||||
REG(regs->base + UART_IM) = UART_IM_RXIM | UART_IM_RTIM;
|
||||
REG(regs->base + UART_IM) |= UART_IM_OEIM | UART_IM_BEIM | UART_IM_FEIM;
|
||||
|
||||
REG(regs->base | UART_IFLS) =
|
||||
REG(regs->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(regs->base | UART_CTL) = UART_CTL_VALUE;
|
||||
REG(regs->base + UART_CTL) = UART_CTL_VALUE;
|
||||
|
||||
/* Baud Rate Generation */
|
||||
REG(regs->base | UART_IBRD) = regs->ibrd;
|
||||
REG(regs->base | UART_FBRD) = regs->fbrd;
|
||||
REG(regs->base + UART_IBRD) = regs->ibrd;
|
||||
REG(regs->base + UART_FBRD) = regs->fbrd;
|
||||
|
||||
/* UART Control: 8N1 with FIFOs */
|
||||
REG(regs->base | UART_LCRH) = UART_LCRH_WLEN_8 | UART_LCRH_FEN;
|
||||
REG(regs->base + UART_LCRH) = UART_LCRH_WLEN_8 | UART_LCRH_FEN;
|
||||
|
||||
/*
|
||||
* Enable hardware flow control (RTS/CTS) if requested.
|
||||
|
@ -316,18 +316,18 @@ uart_init(uint8_t uart)
|
|||
REG(IOC_UARTCTS_UART1) = ioc_input_sel(regs->cts.port, regs->cts.pin);
|
||||
GPIO_PERIPHERAL_CONTROL(GPIO_PORT_TO_BASE(regs->cts.port), GPIO_PIN_MASK(regs->cts.pin));
|
||||
ioc_set_over(regs->cts.port, regs->cts.pin, IOC_OVERRIDE_DIS);
|
||||
REG(UART_1_BASE | UART_CTL) |= UART_CTL_CTSEN;
|
||||
REG(UART_1_BASE + UART_CTL) |= UART_CTL_CTSEN;
|
||||
}
|
||||
|
||||
if(regs->rts.port >= 0) {
|
||||
ioc_set_sel(regs->rts.port, regs->rts.pin, IOC_PXX_SEL_UART1_RTS);
|
||||
GPIO_PERIPHERAL_CONTROL(GPIO_PORT_TO_BASE(regs->rts.port), GPIO_PIN_MASK(regs->rts.pin));
|
||||
ioc_set_over(regs->rts.port, regs->rts.pin, IOC_OVERRIDE_OE);
|
||||
REG(UART_1_BASE | UART_CTL) |= UART_CTL_RTSEN;
|
||||
REG(UART_1_BASE + UART_CTL) |= UART_CTL_RTSEN;
|
||||
}
|
||||
|
||||
/* UART Enable */
|
||||
REG(regs->base | UART_CTL) |= UART_CTL_UARTEN;
|
||||
REG(regs->base + UART_CTL) |= UART_CTL_UARTEN;
|
||||
|
||||
/* Enable UART0 Interrupts */
|
||||
nvic_interrupt_enable(regs->nvic_int);
|
||||
|
@ -354,9 +354,9 @@ uart_write_byte(uint8_t uart, uint8_t b)
|
|||
uart_base = uart_regs[uart].base;
|
||||
|
||||
/* Block if the TX FIFO is full */
|
||||
while(REG(uart_base | UART_FR) & UART_FR_TXFF);
|
||||
while(REG(uart_base + UART_FR) & UART_FR_TXFF);
|
||||
|
||||
REG(uart_base | UART_DR) = b;
|
||||
REG(uart_base + UART_DR) = b;
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
void
|
||||
|
@ -371,18 +371,18 @@ uart_isr(uint8_t uart)
|
|||
|
||||
/* 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_base | UART_MIS) & 0x0000FFFF;
|
||||
mis = REG(uart_base + UART_MIS) & 0x0000FFFF;
|
||||
|
||||
REG(uart_base | UART_ICR) = 0x0000FFBF;
|
||||
REG(uart_base + UART_ICR) = 0x0000FFBF;
|
||||
|
||||
if(mis & (UART_MIS_RXMIS | UART_MIS_RTMIS)) {
|
||||
while(!(REG(uart_base | UART_FR) & UART_FR_RXFE)) {
|
||||
while(!(REG(uart_base + UART_FR) & UART_FR_RXFE)) {
|
||||
if(input_handler[uart] != NULL) {
|
||||
input_handler[uart]((unsigned char)(REG(uart_base | UART_DR) & 0xFF));
|
||||
input_handler[uart]((unsigned char)(REG(uart_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_base | UART_DR);
|
||||
mis = REG(uart_base + UART_DR);
|
||||
}
|
||||
}
|
||||
} else if(mis & (UART_MIS_OEMIS | UART_MIS_BEMIS | UART_MIS_FEMIS)) {
|
||||
|
|
78
cpu/cc2538/dev/vdd3-sensor.c
Normal file
78
cpu/cc2538/dev/vdd3-sensor.c
Normal file
|
@ -0,0 +1,78 @@
|
|||
/*
|
||||
* Copyright (c) 2015, Zolertia - http://www.zolertia.com
|
||||
* Copyright (c) 2015, University of Bristol - http://www.bristol.ac.uk
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in the
|
||||
* documentation and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. Neither the name of the 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-vdd3-sensor
|
||||
* @{
|
||||
*
|
||||
* \file
|
||||
* Driver for the CC2538 VDD3 sensor
|
||||
*/
|
||||
/*---------------------------------------------------------------------------*/
|
||||
#include "contiki.h"
|
||||
#include "lib/sensors.h"
|
||||
#include "dev/vdd3-sensor.h"
|
||||
#include "dev/adc.h"
|
||||
#include "dev/cc2538-sensors.h"
|
||||
|
||||
#include <stdint.h>
|
||||
/*---------------------------------------------------------------------------*/
|
||||
static int
|
||||
value(int type)
|
||||
{
|
||||
int raw = adc_get(SOC_ADC_ADCCON_CH_VDD_3, SOC_ADC_ADCCON_REF_INT,
|
||||
SOC_ADC_ADCCON_DIV_512);
|
||||
|
||||
if(type == CC2538_SENSORS_VALUE_TYPE_RAW) {
|
||||
return raw;
|
||||
} else if(type == CC2538_SENSORS_VALUE_TYPE_CONVERTED) {
|
||||
return raw * (3 * 1190) / (2047 << 4);
|
||||
}
|
||||
|
||||
return CC2538_SENSORS_ERROR;
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
static int
|
||||
configure(int type, int value)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
static int
|
||||
status(int type)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
SENSORS_SENSOR(vdd3_sensor, VDD3_SENSOR, value, configure, status);
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/** @} */
|
71
cpu/cc2538/dev/vdd3-sensor.h
Normal file
71
cpu/cc2538/dev/vdd3-sensor.h
Normal file
|
@ -0,0 +1,71 @@
|
|||
/*
|
||||
* Copyright (c) 2015, Zolertia - http://www.zolertia.com
|
||||
* Copyright (c) 2015, University of Bristol - http://www.bristol.ac.uk
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in the
|
||||
* documentation and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. Neither the name of the 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-sensors
|
||||
* @{
|
||||
*
|
||||
* \defgroup cc2538-vdd3-sensor CC2538 VDD3 Sensor
|
||||
*
|
||||
* Driver for the CC2538 VDD3 sensor
|
||||
*
|
||||
* This driver can return the raw as well as the converted value of the sensor
|
||||
* reading. This is controlled by the type argument of the sensor driver's
|
||||
* value() function. The choices for the type argument are:
|
||||
* - REMOTE_SENSORS_VALUE_TYPE_RAW (value() returns the raw reading)
|
||||
* - REMOTE_SENSORS_VALUE_TYPE_CONVERTED (value() returns mV)
|
||||
* @{
|
||||
*
|
||||
* \file
|
||||
* Header file for the CC2538 VDD3 Sensor Driver
|
||||
*/
|
||||
/*---------------------------------------------------------------------------*/
|
||||
#ifndef VDD3_SENSOR_H_
|
||||
#define VDD3_SENSOR_H_
|
||||
/*---------------------------------------------------------------------------*/
|
||||
#include "lib/sensors.h"
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/**
|
||||
* \name VDD3 sensors
|
||||
* @{
|
||||
*/
|
||||
#define VDD3_SENSOR "VDD3"
|
||||
/** @} */
|
||||
/*---------------------------------------------------------------------------*/
|
||||
extern const struct sensors_sensor vdd3_sensor;
|
||||
/*---------------------------------------------------------------------------*/
|
||||
#endif /* VDD3_SENSOR_H_ */
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
330
cpu/cc2538/startup-gcc.c
Normal file
330
cpu/cc2538/startup-gcc.c
Normal file
|
@ -0,0 +1,330 @@
|
|||
/*
|
||||
* Copyright (C) 2012 Texas Instruments Incorporated - http://www.ti.com/
|
||||
*
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
*
|
||||
* Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in the
|
||||
* documentation and/or other materials provided with the distribution.
|
||||
*
|
||||
* Neither the name of Texas Instruments Incorporated nor the names of
|
||||
* its contributors may be used to endorse or promote products derived
|
||||
* from this software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
|
||||
* A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
|
||||
* OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
|
||||
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
|
||||
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
|
||||
* DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
|
||||
* THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
/**
|
||||
* \addtogroup cc2538
|
||||
* @{
|
||||
*
|
||||
* \file
|
||||
* Startup code for the cc2538 chip, to be used when building with gcc
|
||||
*/
|
||||
#include "contiki.h"
|
||||
#include "reg.h"
|
||||
#include "flash-cca.h"
|
||||
#include "sys-ctrl.h"
|
||||
|
||||
#include <stdint.h>
|
||||
/*---------------------------------------------------------------------------*/
|
||||
extern int main(void);
|
||||
/*---------------------------------------------------------------------------*/
|
||||
#define WEAK_ALIAS(x) __attribute__ ((weak, alias(#x)))
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* System handlers provided here */
|
||||
void reset_handler(void);
|
||||
void nmi_handler(void);
|
||||
void default_handler(void);
|
||||
|
||||
/* System Handler and ISR prototypes implemented elsewhere */
|
||||
void clock_isr(void); /* SysTick Handler */
|
||||
void gpio_port_a_isr(void);
|
||||
void gpio_port_b_isr(void);
|
||||
void gpio_port_c_isr(void);
|
||||
void gpio_port_d_isr(void);
|
||||
void rtimer_isr(void);
|
||||
void cc2538_rf_rx_tx_isr(void);
|
||||
void cc2538_rf_err_isr(void);
|
||||
void udma_isr(void);
|
||||
void udma_err_isr(void);
|
||||
void usb_isr(void) WEAK_ALIAS(default_handler);
|
||||
void uart0_isr(void) WEAK_ALIAS(default_handler);
|
||||
void uart1_isr(void) WEAK_ALIAS(default_handler);
|
||||
|
||||
/* Boot Loader Backdoor selection */
|
||||
#if FLASH_CCA_CONF_BOOTLDR_BACKDOOR
|
||||
/* Backdoor enabled */
|
||||
|
||||
#if FLASH_CCA_CONF_BOOTLDR_BACKDOOR_ACTIVE_HIGH
|
||||
#define FLASH_CCA_BOOTLDR_CFG_ACTIVE_LEVEL FLASH_CCA_BOOTLDR_CFG_ACTIVE_HIGH
|
||||
#else
|
||||
#define FLASH_CCA_BOOTLDR_CFG_ACTIVE_LEVEL 0
|
||||
#endif
|
||||
|
||||
#if ((FLASH_CCA_CONF_BOOTLDR_BACKDOOR_PORT_A_PIN < 0) || (FLASH_CCA_CONF_BOOTLDR_BACKDOOR_PORT_A_PIN > 7))
|
||||
#error Invalid boot loader backdoor pin. Please set FLASH_CCA_CONF_BOOTLDR_BACKDOOR_PORT_A_PIN between 0 and 7 (indicating PA0 - PA7).
|
||||
#endif
|
||||
|
||||
#define FLASH_CCA_BOOTLDR_CFG (FLASH_CCA_BOOTLDR_CFG_ENABLE \
|
||||
| FLASH_CCA_BOOTLDR_CFG_ACTIVE_LEVEL \
|
||||
| (FLASH_CCA_CONF_BOOTLDR_BACKDOOR_PORT_A_PIN << FLASH_CCA_BOOTLDR_CFG_PORT_A_PIN_S))
|
||||
#else
|
||||
#define FLASH_CCA_BOOTLDR_CFG FLASH_CCA_BOOTLDR_CFG_DISABLE
|
||||
#endif
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* Allocate stack space */
|
||||
static unsigned long stack[512];
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* Linker construct indicating .text section location */
|
||||
extern uint8_t _text[0];
|
||||
/*---------------------------------------------------------------------------*/
|
||||
__attribute__ ((section(".flashcca"), used))
|
||||
const flash_cca_lock_page_t __cca = {
|
||||
FLASH_CCA_BOOTLDR_CFG, /* Boot loader backdoor configuration */
|
||||
FLASH_CCA_IMAGE_VALID, /* Image valid */
|
||||
&_text, /* Vector table located at the start of .text */
|
||||
/* Unlock all pages and debug */
|
||||
{ 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF }
|
||||
};
|
||||
/*---------------------------------------------------------------------------*/
|
||||
__attribute__ ((section(".vectors"), used))
|
||||
void(*const vectors[])(void) =
|
||||
{
|
||||
(void (*)(void))((unsigned long)stack + sizeof(stack)), /* Stack pointer */
|
||||
reset_handler, /* Reset handler */
|
||||
nmi_handler, /* The NMI handler */
|
||||
default_handler, /* The hard fault handler */
|
||||
default_handler, /* 4 The MPU fault handler */
|
||||
default_handler, /* 5 The bus fault handler */
|
||||
default_handler, /* 6 The usage fault handler */
|
||||
0, /* 7 Reserved */
|
||||
0, /* 8 Reserved */
|
||||
0, /* 9 Reserved */
|
||||
0, /* 10 Reserved */
|
||||
default_handler, /* 11 SVCall handler */
|
||||
default_handler, /* 12 Debug monitor handler */
|
||||
0, /* 13 Reserved */
|
||||
default_handler, /* 14 The PendSV handler */
|
||||
clock_isr, /* 15 The SysTick handler */
|
||||
gpio_port_a_isr, /* 16 GPIO Port A */
|
||||
gpio_port_b_isr, /* 17 GPIO Port B */
|
||||
gpio_port_c_isr, /* 18 GPIO Port C */
|
||||
gpio_port_d_isr, /* 19 GPIO Port D */
|
||||
0, /* 20 none */
|
||||
uart0_isr, /* 21 UART0 Rx and Tx */
|
||||
uart1_isr, /* 22 UART1 Rx and Tx */
|
||||
default_handler, /* 23 SSI0 Rx and Tx */
|
||||
default_handler, /* 24 I2C Master and Slave */
|
||||
0, /* 25 Reserved */
|
||||
0, /* 26 Reserved */
|
||||
0, /* 27 Reserved */
|
||||
0, /* 28 Reserved */
|
||||
0, /* 29 Reserved */
|
||||
default_handler, /* 30 ADC Sequence 0 */
|
||||
0, /* 31 Reserved */
|
||||
0, /* 32 Reserved */
|
||||
0, /* 33 Reserved */
|
||||
default_handler, /* 34 Watchdog timer, timer 0 */
|
||||
default_handler, /* 35 Timer 0 subtimer A */
|
||||
default_handler, /* 36 Timer 0 subtimer B */
|
||||
default_handler, /* 37 Timer 1 subtimer A */
|
||||
default_handler, /* 38 Timer 1 subtimer B */
|
||||
default_handler, /* 39 Timer 2 subtimer A */
|
||||
default_handler, /* 40 Timer 2 subtimer B */
|
||||
default_handler, /* 41 Analog Comparator 0 */
|
||||
default_handler, /* 42 RFCore Rx/Tx (Alternate) */
|
||||
default_handler, /* 43 RFCore Error (Alternate) */
|
||||
default_handler, /* 44 System Control */
|
||||
default_handler, /* 45 FLASH Control */
|
||||
default_handler, /* 46 AES (Alternate) */
|
||||
default_handler, /* 47 PKA (Alternate) */
|
||||
default_handler, /* 48 SM Timer (Alternate) */
|
||||
default_handler, /* 49 MacTimer (Alternate) */
|
||||
default_handler, /* 50 SSI1 Rx and Tx */
|
||||
default_handler, /* 51 Timer 3 subtimer A */
|
||||
default_handler, /* 52 Timer 3 subtimer B */
|
||||
0, /* 53 Reserved */
|
||||
0, /* 54 Reserved */
|
||||
0, /* 55 Reserved */
|
||||
0, /* 56 Reserved */
|
||||
0, /* 57 Reserved */
|
||||
0, /* 58 Reserved */
|
||||
0, /* 59 Reserved */
|
||||
0, /* 60 Reserved */
|
||||
0, /* 61 Reserved */
|
||||
udma_isr, /* 62 uDMA */
|
||||
udma_err_isr, /* 63 uDMA Error */
|
||||
0, /* 64 64-155 are not in use */
|
||||
0, /* 65 */
|
||||
0, /* 66 */
|
||||
0, /* 67 */
|
||||
0, /* 68 */
|
||||
0, /* 69 */
|
||||
0, /* 70 */
|
||||
0, /* 71 */
|
||||
0, /* 72 */
|
||||
0, /* 73 */
|
||||
0, /* 74 */
|
||||
0, /* 75 */
|
||||
0, /* 76 */
|
||||
0, /* 77 */
|
||||
0, /* 78 */
|
||||
0, /* 79 */
|
||||
0, /* 80 */
|
||||
0, /* 81 */
|
||||
0, /* 82 */
|
||||
0, /* 83 */
|
||||
0, /* 84 */
|
||||
0, /* 85 */
|
||||
0, /* 86 */
|
||||
0, /* 87 */
|
||||
0, /* 88 */
|
||||
0, /* 89 */
|
||||
0, /* 90 */
|
||||
0, /* 91 */
|
||||
0, /* 92 */
|
||||
0, /* 93 */
|
||||
0, /* 94 */
|
||||
0, /* 95 */
|
||||
0, /* 96 */
|
||||
0, /* 97 */
|
||||
0, /* 98 */
|
||||
0, /* 99 */
|
||||
0, /* 100 */
|
||||
0, /* 101 */
|
||||
0, /* 102 */
|
||||
0, /* 103 */
|
||||
0, /* 104 */
|
||||
0, /* 105 */
|
||||
0, /* 106 */
|
||||
0, /* 107 */
|
||||
0, /* 108 */
|
||||
0, /* 109 */
|
||||
0, /* 110 */
|
||||
0, /* 111 */
|
||||
0, /* 112 */
|
||||
0, /* 113 */
|
||||
0, /* 114 */
|
||||
0, /* 115 */
|
||||
0, /* 116 */
|
||||
0, /* 117 */
|
||||
0, /* 118 */
|
||||
0, /* 119 */
|
||||
0, /* 120 */
|
||||
0, /* 121 */
|
||||
0, /* 122 */
|
||||
0, /* 123 */
|
||||
0, /* 124 */
|
||||
0, /* 125 */
|
||||
0, /* 126 */
|
||||
0, /* 127 */
|
||||
0, /* 128 */
|
||||
0, /* 129 */
|
||||
0, /* 130 */
|
||||
0, /* 131 */
|
||||
0, /* 132 */
|
||||
0, /* 133 */
|
||||
0, /* 134 */
|
||||
0, /* 135 */
|
||||
0, /* 136 */
|
||||
0, /* 137 */
|
||||
0, /* 138 */
|
||||
0, /* 139 */
|
||||
0, /* 140 */
|
||||
0, /* 141 */
|
||||
0, /* 142 */
|
||||
0, /* 143 */
|
||||
0, /* 144 */
|
||||
0, /* 145 */
|
||||
0, /* 146 */
|
||||
0, /* 147 */
|
||||
0, /* 148 */
|
||||
0, /* 149 */
|
||||
0, /* 150 */
|
||||
0, /* 151 */
|
||||
0, /* 152 */
|
||||
0, /* 153 */
|
||||
0, /* 154 */
|
||||
0, /* 155 */
|
||||
usb_isr, /* 156 USB */
|
||||
cc2538_rf_rx_tx_isr, /* 157 RFCORE RX/TX */
|
||||
cc2538_rf_err_isr, /* 158 RFCORE Error */
|
||||
default_handler, /* 159 AES */
|
||||
default_handler, /* 160 PKA */
|
||||
rtimer_isr, /* 161 SM Timer */
|
||||
default_handler, /* 162 MACTimer */
|
||||
};
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* Linker constructs indicating .data and .bss segment locations */
|
||||
extern unsigned long _etext;
|
||||
extern unsigned long _data;
|
||||
extern unsigned long _edata;
|
||||
extern unsigned long _bss;
|
||||
extern unsigned long _ebss;
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* Weak interrupt handlers. */
|
||||
void
|
||||
nmi_handler(void)
|
||||
{
|
||||
reset_handler();
|
||||
while(1);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
void
|
||||
default_handler(void)
|
||||
{
|
||||
while(1);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
void
|
||||
reset_handler(void)
|
||||
{
|
||||
unsigned long *pul_src, *pul_dst;
|
||||
|
||||
REG(SYS_CTRL_EMUOVR) = 0xFF;
|
||||
|
||||
/* Copy the data segment initializers from flash to SRAM. */
|
||||
pul_src = &_etext;
|
||||
|
||||
for(pul_dst = &_data; pul_dst < &_edata;) {
|
||||
*pul_dst++ = *pul_src++;
|
||||
}
|
||||
|
||||
/* Zero-fill the bss segment. */
|
||||
__asm(" ldr r0, =_bss\n"
|
||||
" ldr r1, =_ebss\n"
|
||||
" mov r2, #0\n"
|
||||
" .thumb_func\n"
|
||||
"zero_loop:\n"
|
||||
" cmp r0, r1\n"
|
||||
" it lt\n"
|
||||
" strlt r2, [r0], #4\n" " blt zero_loop");
|
||||
|
||||
/* call the application's entry point. */
|
||||
main();
|
||||
|
||||
/* End here if main () returns */
|
||||
while(1);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
|
||||
/** @} */
|
|
@ -6,6 +6,7 @@ OBJCOPY = arm-none-eabi-objcopy
|
|||
OBJDUMP = arm-none-eabi-objdump
|
||||
NM = arm-none-eabi-nm
|
||||
SIZE = arm-none-eabi-size
|
||||
SREC_CAT = srec_cat
|
||||
|
||||
### TI CC26xxware out-of-tree
|
||||
### TI_CC26XXWARE is the home directory of the cc26xxware
|
||||
|
@ -106,9 +107,12 @@ CUSTOM_RULE_LINK=1
|
|||
$(TRACE_LD)
|
||||
$(Q)$(LD) $(LDFLAGS) ${filter-out $(LDSCRIPT) %.a,$^} ${filter %.a,$^} $(TARGET_LIBFILES) -lm -o $@
|
||||
|
||||
%.hex: %.elf
|
||||
%.i16hex: %.elf
|
||||
$(OBJCOPY) -O ihex $< $@
|
||||
|
||||
%.hex: %.i16hex
|
||||
$(SREC_CAT) $< -intel -o $@ -intel
|
||||
|
||||
%.bin: %.elf
|
||||
$(OBJCOPY) $(OBJCOPY_FLAGS) $< $@
|
||||
|
||||
|
|
|
@ -167,7 +167,7 @@ clock_delay_usec(uint16_t len)
|
|||
* Wait for TBEN to clear. CC26xxware does not provide us with a convenient
|
||||
* function, hence the direct register access here
|
||||
*/
|
||||
while(HWREG(GPT0_BASE | GPT_O_CTL) & GPT_CTL_TBEN);
|
||||
while(HWREG(GPT0_BASE + GPT_O_CTL) & GPT_CTL_TBEN);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/**
|
||||
|
|
|
@ -267,15 +267,17 @@ const output_config_t *tx_power_current = &output_power[0];
|
|||
/*---------------------------------------------------------------------------*/
|
||||
/* RF interrupts */
|
||||
#define RX_IRQ IRQ_IEEE_RX_ENTRY_DONE
|
||||
#define TX_IRQ IRQ_IEEE_TX_FRAME
|
||||
#define TX_ACK_IRQ IRQ_IEEE_TX_ACK
|
||||
#define ERROR_IRQ IRQ_INTERNAL_ERROR
|
||||
|
||||
/* Those IRQs are enabled all the time */
|
||||
#define ENABLED_IRQS (RX_IRQ + ERROR_IRQ)
|
||||
|
||||
/*
|
||||
* We don't really care about TX ISR, we just use it to bring the CM3 out
|
||||
* of sleep, which it enters while the RF is TXing
|
||||
* We only enable this right before starting frame TX, so we can sleep while
|
||||
* the TX is ongoing
|
||||
*/
|
||||
#define ENABLED_IRQS (RX_IRQ + TX_IRQ + ERROR_IRQ)
|
||||
#define LAST_FG_CMD_DONE IRQ_LAST_FG_COMMAND_DONE
|
||||
|
||||
#define cc26xx_rf_cpe0_isr RFCCPE0IntHandler
|
||||
#define cc26xx_rf_cpe1_isr RFCCPE1IntHandler
|
||||
|
@ -464,7 +466,7 @@ rf_is_accessible(void)
|
|||
{
|
||||
if(ti_lib_prcm_rf_ready() &&
|
||||
ti_lib_prcm_power_domain_status(PRCM_DOMAIN_RFCORE) ==
|
||||
PRCM_DOMAIN_POWER_ON) {
|
||||
PRCM_DOMAIN_POWER_ON) {
|
||||
return 1;
|
||||
}
|
||||
return 0;
|
||||
|
@ -937,6 +939,7 @@ init_rf_params(void)
|
|||
BITVALUE(CMD_IEEE_RX, frameFiltOpt, defaultPend, 0) |
|
||||
BITVALUE(CMD_IEEE_RX, frameFiltOpt, bPendDataReqOnly, 0) |
|
||||
BITVALUE(CMD_IEEE_RX, frameFiltOpt, bPanCoord, 0) |
|
||||
BITVALUE(CMD_IEEE_RX, frameFiltOpt, maxFrameVersion, 1) |
|
||||
BITVALUE(CMD_IEEE_RX, frameFiltOpt, bStrictLenFilter, 0);
|
||||
/* Receive all frame types */
|
||||
GET_FIELD(cmd_ieee_rx_buf, CMD_IEEE_RX, frameTypes) =
|
||||
|
@ -1294,6 +1297,10 @@ transmit(unsigned short transmit_len)
|
|||
GET_FIELD(cmd_immediate_buf, CMD_IEEE_TX, payloadLen) = transmit_len;
|
||||
GET_FIELD(cmd_immediate_buf, CMD_IEEE_TX, pPayload) = tx_buf;
|
||||
|
||||
/* Enable the LAST_FG_COMMAND_DONE interrupt, which will wake us up */
|
||||
HWREG(RFC_DBELL_NONBUF_BASE + RFC_DBELL_O_RFCPEIEN) = ENABLED_IRQS +
|
||||
LAST_FG_CMD_DONE;
|
||||
|
||||
ret = rf_send_cmd((uint32_t)cmd_immediate_buf, &cmd_status);
|
||||
|
||||
if(ret) {
|
||||
|
@ -1334,9 +1341,11 @@ transmit(unsigned short transmit_len)
|
|||
ENERGEST_OFF(ENERGEST_TYPE_TRANSMIT);
|
||||
ENERGEST_ON(ENERGEST_TYPE_LISTEN);
|
||||
|
||||
if(was_off) {
|
||||
off();
|
||||
}
|
||||
/*
|
||||
* Disable LAST_FG_COMMAND_DONE interrupt. We don't really care about it
|
||||
* except when we are transmitting
|
||||
*/
|
||||
HWREG(RFC_DBELL_NONBUF_BASE + RFC_DBELL_O_RFCPEIEN) = ENABLED_IRQS;
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
|
|
@ -66,7 +66,7 @@
|
|||
#define CC26XX_RF_AUTOACK 1
|
||||
#endif /* CC26XX_RF_CONF_AUTOACK */
|
||||
|
||||
#if defined (CC26XX_RF_CONF_BLE_SUPPORT) && (CC26XX_MODEL_CPU_VARIANT == 2650)
|
||||
#if (CC26XX_RF_CONF_BLE_SUPPORT) && (CC26XX_MODEL_CPU_VARIANT == 2650)
|
||||
#define CC26XX_RF_BLE_SUPPORT CC26XX_RF_CONF_BLE_SUPPORT
|
||||
#else
|
||||
#define CC26XX_RF_BLE_SUPPORT 0
|
||||
|
|
|
@ -91,7 +91,7 @@ cc26xx_rtc_get_next_trigger()
|
|||
if(HWREG(AON_RTC_BASE + AON_RTC_O_CHCTL) & AON_RTC_CHCTL_CH0_EN) {
|
||||
rtimer_clock_t ch0 = ti_lib_aon_rtc_compare_value_get(AON_RTC_CH2);
|
||||
|
||||
return RTIMER_CLOCK_LT(ch0 ,ch2) ? ch0 : ch2;
|
||||
return RTIMER_CLOCK_LT(ch0, ch2) ? ch0 : ch2;
|
||||
}
|
||||
|
||||
return ch2;
|
||||
|
|
|
@ -54,7 +54,7 @@
|
|||
void
|
||||
watchdog_init(void)
|
||||
{
|
||||
ti_lib_wathdog_reload_set(0xFFFFF);
|
||||
ti_lib_watchdog_reload_set(0xFFFFF);
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/**
|
||||
|
@ -63,7 +63,7 @@ watchdog_init(void)
|
|||
void
|
||||
watchdog_start(void)
|
||||
{
|
||||
ti_lib_wathdog_reset_enable();
|
||||
ti_lib_watchdog_reset_enable();
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/**
|
||||
|
@ -72,7 +72,7 @@ watchdog_start(void)
|
|||
void
|
||||
watchdog_periodic(void)
|
||||
{
|
||||
ti_lib_wathdog_int_clear();
|
||||
ti_lib_watchdog_int_clear();
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/**
|
||||
|
|
|
@ -640,24 +640,24 @@
|
|||
/* watchdog.h */
|
||||
#include "driverlib/watchdog.h"
|
||||
|
||||
#define ti_lib_wathdog_running(...) WatchdogRunning(__VA_ARGS__)
|
||||
#define ti_lib_wathdog_enable(...) WatchdogEnable(__VA_ARGS__)
|
||||
#define ti_lib_wathdog_reset_enable(...) WatchdogResetEnable(__VA_ARGS__)
|
||||
#define ti_lib_wathdog_reset_disable(...) WatchdogResetDisable(__VA_ARGS__)
|
||||
#define ti_lib_wathdog_lock(...) WatchdogLock(__VA_ARGS__)
|
||||
#define ti_lib_wathdog_unlock(...) WatchdogUnlock(__VA_ARGS__)
|
||||
#define ti_lib_wathdog_lock_state(...) WatchdogLockState(__VA_ARGS__)
|
||||
#define ti_lib_wathdog_reload_set(...) WatchdogReloadSet(__VA_ARGS__)
|
||||
#define ti_lib_wathdog_reload_get(...) WatchdogReloadGet(__VA_ARGS__)
|
||||
#define ti_lib_wathdog_value_get(...) WatchdogValueGet(__VA_ARGS__)
|
||||
#define ti_lib_wathdog_int_register(...) WatchdogIntRegister(__VA_ARGS__)
|
||||
#define ti_lib_wathdog_int_unregister(...) WatchdogIntUnregister(__VA_ARGS__)
|
||||
#define ti_lib_wathdog_int_enable(...) WatchdogIntEnable(__VA_ARGS__)
|
||||
#define ti_lib_wathdog_int_status(...) WatchdogIntStatus(__VA_ARGS__)
|
||||
#define ti_lib_wathdog_int_clear(...) WatchdogIntClear(__VA_ARGS__)
|
||||
#define ti_lib_wathdog_int_type_set(...) WatchdogIntTypeSet(__VA_ARGS__)
|
||||
#define ti_lib_wathdog_stall_enable(...) WatchdogStallEnable(__VA_ARGS__)
|
||||
#define ti_lib_wathdog_stall_disable(...) WatchdogStallDisable(__VA_ARGS__)
|
||||
#define ti_lib_watchdog_running(...) WatchdogRunning(__VA_ARGS__)
|
||||
#define ti_lib_watchdog_enable(...) WatchdogEnable(__VA_ARGS__)
|
||||
#define ti_lib_watchdog_reset_enable(...) WatchdogResetEnable(__VA_ARGS__)
|
||||
#define ti_lib_watchdog_reset_disable(...) WatchdogResetDisable(__VA_ARGS__)
|
||||
#define ti_lib_watchdog_lock(...) WatchdogLock(__VA_ARGS__)
|
||||
#define ti_lib_watchdog_unlock(...) WatchdogUnlock(__VA_ARGS__)
|
||||
#define ti_lib_watchdog_lock_state(...) WatchdogLockState(__VA_ARGS__)
|
||||
#define ti_lib_watchdog_reload_set(...) WatchdogReloadSet(__VA_ARGS__)
|
||||
#define ti_lib_watchdog_reload_get(...) WatchdogReloadGet(__VA_ARGS__)
|
||||
#define ti_lib_watchdog_value_get(...) WatchdogValueGet(__VA_ARGS__)
|
||||
#define ti_lib_watchdog_int_register(...) WatchdogIntRegister(__VA_ARGS__)
|
||||
#define ti_lib_watchdog_int_unregister(...) WatchdogIntUnregister(__VA_ARGS__)
|
||||
#define ti_lib_watchdog_int_enable(...) WatchdogIntEnable(__VA_ARGS__)
|
||||
#define ti_lib_watchdog_int_status(...) WatchdogIntStatus(__VA_ARGS__)
|
||||
#define ti_lib_watchdog_int_clear(...) WatchdogIntClear(__VA_ARGS__)
|
||||
#define ti_lib_watchdog_int_type_set(...) WatchdogIntTypeSet(__VA_ARGS__)
|
||||
#define ti_lib_watchdog_stall_enable(...) WatchdogStallEnable(__VA_ARGS__)
|
||||
#define ti_lib_watchdog_stall_disable(...) WatchdogStallDisable(__VA_ARGS__)
|
||||
/*---------------------------------------------------------------------------*/
|
||||
#endif /* TI_LIB_H_ */
|
||||
/*---------------------------------------------------------------------------*/
|
||||
|
|
|
@ -1,172 +0,0 @@
|
|||
Contiki REST/CoAP Quickstart using Econotags
|
||||
======================================
|
||||
|
||||
Contiki has an implementation of the IETF CORE (Constrained RESTful
|
||||
Environments) working group's CoAP layer (Constrained Application
|
||||
Protocol). CoAP is a RESTful application layer that uses HTTP-like
|
||||
methods (GET, POST, PUT, DELETE) to interact with constrained
|
||||
networks. CoAP operates over UDP and supports reliable transmission.
|
||||
|
||||
This tutorial will show you how to run Contiki's CoAP demo on Redwire
|
||||
Econotags using an RPL border-router.
|
||||
|
||||
1) Run a RPL border-router and tunnel
|
||||
---------------------------------------------------------------
|
||||
|
||||
See [the RPL
|
||||
HOWTO](http://mc1322x.devl.org/repos/contiki-mc1322x/cpu/mc1322x/doc/rpl-tutorial.md)
|
||||
for details about running a RPL border-router.
|
||||
|
||||
2) Build and run the `rest-server-example` on a second Econotag
|
||||
----------------------------------------
|
||||
|
||||
__The following must be done on the contiki-mc1322x.git tree__
|
||||
|
||||
git clone git://git.devl.org/git/malvira/contiki-mc1322x.git
|
||||
|
||||
__Contiki CVS is currently down and the new SCM system hasn't been set
|
||||
up yet. The necessary changes will be pushed as soon as the new SCM is
|
||||
available. - 6 Februrary 2011__
|
||||
|
||||
To build the rest-server-example:
|
||||
|
||||
cd contiki-mc1322x/examples/rest-example
|
||||
make TARGET=redbee-econotag
|
||||
|
||||
This will produce the binary image
|
||||
`rest-server-example_redbee-econotag.bin`, which you can load directly
|
||||
on to an mc1322x and execute.
|
||||
|
||||
mc1322x-load.pl -f rest-server-example_redbee-econotag.bin -t /dev/ttyUSB3
|
||||
|
||||
Then press the reset button to connect to the bootloader.
|
||||
|
||||
In this example, we are loading the CoAP server on to the econotag on `/dev/ttyUSB3`
|
||||
|
||||
You should see boot up messages similar to this:
|
||||
|
||||
CONNECT
|
||||
Size: 62096 bytes
|
||||
Sending rest-server-example_redbee-econotag.bin
|
||||
done sending files.
|
||||
performing ring osc cal
|
||||
crm_status: 0xc0000
|
||||
sys_cntl: 0x18
|
||||
ring osc cal complete
|
||||
cal_count: 0x17e17e0
|
||||
cal factor: 100
|
||||
hib_wake_secs: 2000
|
||||
loading rime address from flash.
|
||||
Rime started with address 00:50:C2:AB:C0:00:00:23
|
||||
nullmac nullrdc, channel check rate 100 Hz, radio channel 26
|
||||
Tentative link-local IPv6 address
|
||||
fe80:0000:0000:0000:0250:c2ab:c000:0023
|
||||
Tentative global IPv6 address aaaa:0000:0000:0000:0250:c2ab:c000:0023
|
||||
Starting 'Rest Server Example'
|
||||
COAP Server
|
||||
|
||||
The last line indicates that the server will be using
|
||||
COAP. As an alternative, you can build the server to use HTTP instead with:
|
||||
|
||||
make TARGET=redbee-econotag WITH_COAP=0
|
||||
|
||||
3) Download and install the `Copper` Firefox Plugin
|
||||
-----------------------------------------------------
|
||||
|
||||
The `Copper` Plugin for Firefox provides the `coap:` URL access method
|
||||
as well as an interface to easily send `coap` requests.
|
||||
|
||||
Download and install the plugin from here:
|
||||
|
||||
+ [Copper plugin homepage](http://people.inf.ethz.ch/~mkovatsc/)
|
||||
+ Install link:[copper-0.3.0pre2.xpi](http://people.inf.ethz.ch/~mkovatsc/resources/copper/copper-0.3.0pre2.xpi)
|
||||
|
||||
4) Open Copper
|
||||
--------------
|
||||
|
||||
Open a new Firefox tab and click on the orange CU button in the lower
|
||||
right.
|
||||
|
||||
[](http://mc1322x.devl.org/files/coap-blanktab.png)
|
||||
|
||||
The initial CU screen will look like this:
|
||||
|
||||
[](http://mc1322x.devl.org/files/coap-opencu.png)
|
||||
|
||||
Type in the the URL of the coap node with the default port number of
|
||||
"61616":
|
||||
|
||||
[](http://mc1322x.devl.org/files/coap-url.png)
|
||||
|
||||
+ Don't forget the brackets ( [ ] ) in the URL
|
||||
|
||||
+ Make sure to use the IPv6 address of your coap server. You can get
|
||||
this from the boot up messages or from the webpage served by your
|
||||
border-router.
|
||||
|
||||
+ You must always press Enter after changing the URL.
|
||||
|
||||
5) GET `.well-known/core` resources
|
||||
------------------------------------
|
||||
|
||||
Now click on the red "./well-known/core" button: this changes the URL
|
||||
to the `.well-known/core` resource.
|
||||
|
||||
Then click GET to perform a get. You should see an acknowledgement
|
||||
that the GET was successful (returns 200 OK). The payload should
|
||||
return:
|
||||
|
||||
</helloworld>;n="HelloWorld",</led>;n="LedControl",</light>;n="Light
|
||||
|
||||
Which is are the well-known resources that this node advertises; see
|
||||
the [COAP
|
||||
specification](https://datatracker.ietf.org/doc/draft-ietf-core-coap/)
|
||||
for details.
|
||||
|
||||
[](http://mc1322x.devl.org/files/coap-wellknown.png)
|
||||
|
||||
6) PUT,POST the `led` resource state
|
||||
------------------------------------
|
||||
|
||||
You can PUT or POST to change the state of the LED.
|
||||
|
||||
Type in the following URL and press enter:
|
||||
|
||||
coap://[aaaa::250:c2ff:fea8:c48e]:61616/led?color=green
|
||||
|
||||
Be sure to use the proper IP address. For this URL: we will perform
|
||||
actions on the `led` resource with a query string of `color=green`.
|
||||
|
||||
In the payload, type:
|
||||
|
||||
mode=on
|
||||
|
||||
That is the payload that will be PUT or POSTed. The COAP server
|
||||
detects the mode string and activates the LED accordingly (with the
|
||||
color chosen by the query string).
|
||||
|
||||
Then click PUT or POST to perform the request.
|
||||
|
||||
[](http://mc1322x.devl.org/files/coap-led.png)
|
||||
|
||||
You should get a successful return code (200 OK) and the green LED
|
||||
should turn on. If you PUT/POST `mode=off` the led will turn off.
|
||||
|
||||
The econotag only has two LEDs: a green and a red. The red LED is used
|
||||
to indicate radio transmission by default and so cannot be used in
|
||||
this demo. The Coniki blue LED is connected to GPIO 43. You can toggle
|
||||
it, but you won't see anything unless you hook something up to this
|
||||
pin.
|
||||
|
||||
7) Other resources
|
||||
------------------
|
||||
|
||||
The `rest-server-example` also provides `helloworld` and `light` as
|
||||
GETtable resources.
|
||||
|
||||
coap://[aaaa::250:c2ff:fea8:c48e]:61616/helloworld
|
||||
coap://[aaaa::250:c2ff:fea8:c48e]:61616/light
|
||||
|
||||
The econotag does not have a light sensor. The light resource will
|
||||
always return 0. At a latter date, this sensor will be connected to
|
||||
one of the ADC pins.
|
|
@ -50,10 +50,10 @@ void halInternalGetMfgTokenData(void *data, uint16_t ID, uint8_t index, uint8_t
|
|||
MEMCOPY(ram, eui64, 8 /*EUI64_SIZE*/);
|
||||
} else {
|
||||
//read from the Information Blocks. The token ID is only the
|
||||
//bottom 16bits of the token's actual address. Since the info blocks
|
||||
//exist in the range DATA_BIG_INFO_BASE-DATA_BIG_INFO_END, we need
|
||||
//to OR the ID with DATA_BIG_INFO_BASE to get the real address.
|
||||
uint32_t realAddress = (DATA_BIG_INFO_BASE|ID) + (len*index);
|
||||
//DATA_BIG_INFO_BASE-relative 16-bit offset of the token. Since the
|
||||
//info blocks exist in the range DATA_BIG_INFO_BASE-DATA_BIG_INFO_END,
|
||||
//we need to add the ID to DATA_BIG_INFO_BASE to get the real address.
|
||||
uint32_t realAddress = (DATA_BIG_INFO_BASE+ID) + (len*index);
|
||||
uint8_t *flash = (uint8_t *)realAddress;
|
||||
|
||||
|
||||
|
@ -77,7 +77,7 @@ void halInternalGetMfgTokenData(void *data, uint16_t ID, uint8_t index, uint8_t
|
|||
void halInternalSetMfgTokenData(uint16_t token, void *data, uint8_t len)
|
||||
{
|
||||
StStatus flashStatus;
|
||||
uint32_t realAddress = (DATA_BIG_INFO_BASE|token);
|
||||
uint32_t realAddress = (DATA_BIG_INFO_BASE+token);
|
||||
uint8_t * flash = (uint8_t *)realAddress;
|
||||
uint32_t i;
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue