]> oss.titaniummirror.com Git - tinyos-2.x.git/commitdiff
Removed old CC2420 architecture, preparing to insert better organized code structure
authorrincon <rincon>
Wed, 4 Jul 2007 00:34:17 +0000 (00:34 +0000)
committerrincon <rincon>
Wed, 4 Jul 2007 00:34:17 +0000 (00:34 +0000)
51 files changed:
tos/chips/cc2420/AlarmMultiplexC.nc [deleted file]
tos/chips/cc2420/CC2420.h [deleted file]
tos/chips/cc2420/CC2420AckLpl.h [deleted file]
tos/chips/cc2420/CC2420AckLplC.nc [deleted file]
tos/chips/cc2420/CC2420AckLplP.nc [deleted file]
tos/chips/cc2420/CC2420ActiveMessageC.nc [deleted file]
tos/chips/cc2420/CC2420ActiveMessageP.nc [deleted file]
tos/chips/cc2420/CC2420Cca.nc [deleted file]
tos/chips/cc2420/CC2420Config.nc [deleted file]
tos/chips/cc2420/CC2420ControlC.nc [deleted file]
tos/chips/cc2420/CC2420ControlP.nc [deleted file]
tos/chips/cc2420/CC2420CsmaC.nc [deleted file]
tos/chips/cc2420/CC2420CsmaP.nc [deleted file]
tos/chips/cc2420/CC2420DutyCycle.nc [deleted file]
tos/chips/cc2420/CC2420DutyCycleC.nc [deleted file]
tos/chips/cc2420/CC2420DutyCycleP.nc [deleted file]
tos/chips/cc2420/CC2420Fifo.nc [deleted file]
tos/chips/cc2420/CC2420LplDummyC.nc [deleted file]
tos/chips/cc2420/CC2420LplDummyP.nc [deleted file]
tos/chips/cc2420/CC2420NoAckLpl.h [deleted file]
tos/chips/cc2420/CC2420NoAckLplC.nc [deleted file]
tos/chips/cc2420/CC2420NoAckLplP.nc [deleted file]
tos/chips/cc2420/CC2420Packet.nc [deleted file]
tos/chips/cc2420/CC2420PacketC.nc [deleted file]
tos/chips/cc2420/CC2420Power.nc [deleted file]
tos/chips/cc2420/CC2420Ram.nc [deleted file]
tos/chips/cc2420/CC2420Receive.nc [deleted file]
tos/chips/cc2420/CC2420ReceiveC.nc [deleted file]
tos/chips/cc2420/CC2420ReceiveP.nc [deleted file]
tos/chips/cc2420/CC2420Register.nc [deleted file]
tos/chips/cc2420/CC2420SpiC.nc [deleted file]
tos/chips/cc2420/CC2420SpiImplP.nc [deleted file]
tos/chips/cc2420/CC2420SpiP.nc [deleted file]
tos/chips/cc2420/CC2420Strobe.nc [deleted file]
tos/chips/cc2420/CC2420TinyosNetworkC.nc [deleted file]
tos/chips/cc2420/CC2420TinyosNetworkP.nc [deleted file]
tos/chips/cc2420/CC2420Transmit.nc [deleted file]
tos/chips/cc2420/CC2420TransmitC.nc [deleted file]
tos/chips/cc2420/CC2420TransmitP.nc [deleted file]
tos/chips/cc2420/IEEE802154.h [deleted file]
tos/chips/cc2420/PacketLink.nc [deleted file]
tos/chips/cc2420/PacketLinkC.nc [deleted file]
tos/chips/cc2420/PacketLinkDummyC.nc [deleted file]
tos/chips/cc2420/PacketLinkDummyP.nc [deleted file]
tos/chips/cc2420/PacketLinkP.nc [deleted file]
tos/chips/cc2420/README.txt [deleted file]
tos/chips/cc2420/RadioBackoff.nc [deleted file]
tos/chips/cc2420/UniqueReceiveC.nc [deleted file]
tos/chips/cc2420/UniqueReceiveP.nc [deleted file]
tos/chips/cc2420/UniqueSendC.nc [deleted file]
tos/chips/cc2420/UniqueSendP.nc [deleted file]

diff --git a/tos/chips/cc2420/AlarmMultiplexC.nc b/tos/chips/cc2420/AlarmMultiplexC.nc
deleted file mode 100644 (file)
index a63a925..0000000
+++ /dev/null
@@ -1,57 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Arch Rock Corporation
- * All rights reserved.
- *
- * 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 the Arch Rock Corporation 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
- * ARCHED ROCK OR ITS 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
- */
-
-/**
- * A component that multiplexes the use of an alarm. The assumption is
- * that its use is mutually exclusive and users check whether the
- * events are for them.
- *
- * @author Jonathan Hui <jhui@archrock.com>
- * @version $Revision$ $Date$
- */
-
-#include <Timer.h>
-
-configuration AlarmMultiplexC {
-
-  provides interface Init;
-  provides interface Alarm<T32khz,uint32_t> as Alarm32khz32;
-
-}
-
-implementation {
-
-  components new HplCC2420AlarmC() as Alarm;
-
-  Init = Alarm;
-  Alarm32khz32 = Alarm;
-
-}
diff --git a/tos/chips/cc2420/CC2420.h b/tos/chips/cc2420/CC2420.h
deleted file mode 100644 (file)
index 9166510..0000000
+++ /dev/null
@@ -1,362 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Arch Rock Corporation
- * All rights reserved.
- *
- * 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 the Arch Rock Corporation 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
- * ARCHED ROCK OR ITS 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
- *
- * @author Jonathan Hui <jhui@archrock.com>
- * @author David Moss
- * @version $Revision$ $Date$
- */
-
-#ifndef __CC2420_H__
-#define __CC2420_H__
-
-typedef uint8_t cc2420_status_t;
-
-/**
- * CC2420 header.  An I-frame (interoperability frame) header has an 
- * extra network byte specified by 6LowPAN
- */
-typedef nx_struct cc2420_header_t {
-  nxle_uint8_t length;
-  nxle_uint16_t fcf;
-  nxle_uint8_t dsn;
-  nxle_uint16_t destpan;
-  nxle_uint16_t dest;
-  nxle_uint16_t src;
-  
-  /** I-Frame 6LowPAN interoperability byte */
-#ifdef CC2420_IFRAME_TYPE
-  nxle_uint8_t network;
-#endif
-
-  nxle_uint8_t type;
-} cc2420_header_t;
-  
-/**
- * CC2420 Packet Footer
- */
-typedef nx_struct cc2420_footer_t {
-} cc2420_footer_t;
-
-/**
- * CC2420 Packet metadata. Contains extra information about the message
- * that will not be transmitted
- */
-typedef nx_struct cc2420_metadata_t {
-  nx_uint8_t tx_power;
-  nx_uint8_t rssi;
-  nx_uint8_t lqi;
-  nx_bool crc;
-  nx_bool ack;
-  nx_uint16_t time;
-  nx_uint16_t rxInterval;
-
-  /** Packet Link Metadata */
-#ifdef PACKET_LINK
-  nx_uint16_t maxRetries;
-  nx_uint16_t retryDelay;
-#endif
-
-} cc2420_metadata_t;
-
-
-typedef nx_struct cc2420_packet_t {
-  cc2420_header_t packet;
-  nx_uint8_t data[];
-} cc2420_packet_t;
-
-
-#ifndef TOSH_DATA_LENGTH
-#define TOSH_DATA_LENGTH 28
-#endif
-
-#ifndef CC2420_DEF_CHANNEL
-#define CC2420_DEF_CHANNEL 26
-#endif
-
-#ifndef CC2420_DEF_RFPOWER
-#define CC2420_DEF_RFPOWER 31
-#endif
-
-/**
- * Ideally, your receive history size should be equal to the number of
- * RF neighbors your node will have
- */
-#ifndef RECEIVE_HISTORY_SIZE
-#define RECEIVE_HISTORY_SIZE 4
-#endif
-
-/** 
- * The 6LowPAN ID has yet to be defined for a TinyOS network.
- */
-#ifndef TINYOS_6LOWPAN_NETWORK_ID
-#define TINYOS_6LOWPAN_NETWORK_ID 0x0
-#endif
-
-
-enum {
-  // size of the header not including the length byte
-  MAC_HEADER_SIZE = sizeof( cc2420_header_t ) - 1,
-  // size of the footer (FCS field)
-  MAC_FOOTER_SIZE = sizeof( uint16_t ),
-  // MDU
-  MAC_PACKET_SIZE = MAC_HEADER_SIZE + TOSH_DATA_LENGTH + MAC_FOOTER_SIZE,
-};
-
-enum cc2420_enums {
-  CC2420_TIME_ACK_TURNAROUND = 7, // jiffies
-  CC2420_TIME_VREN = 20,          // jiffies
-  CC2420_TIME_SYMBOL = 2,         // 2 symbols / jiffy
-  CC2420_BACKOFF_PERIOD = ( 20 / CC2420_TIME_SYMBOL ), // symbols
-  CC2420_MIN_BACKOFF = ( 20 / CC2420_TIME_SYMBOL ),  // platform specific?
-  CC2420_ACK_WAIT_DELAY = 128,    // jiffies
-};
-
-enum cc2420_status_enums {
-  CC2420_STATUS_RSSI_VALID = 1 << 1,
-  CC2420_STATUS_LOCK = 1 << 2,
-  CC2420_STATUS_TX_ACTIVE = 1 << 3,
-  CC2420_STATUS_ENC_BUSY = 1 << 4,
-  CC2420_STATUS_TX_UNDERFLOW = 1 << 5,
-  CC2420_STATUS_XOSC16M_STABLE = 1 << 6,
-};
-
-enum cc2420_config_reg_enums {
-  CC2420_SNOP = 0x00,
-  CC2420_SXOSCON = 0x01,
-  CC2420_STXCAL = 0x02,
-  CC2420_SRXON = 0x03,
-  CC2420_STXON = 0x04,
-  CC2420_STXONCCA = 0x05,
-  CC2420_SRFOFF = 0x06,
-  CC2420_SXOSCOFF = 0x07,
-  CC2420_SFLUSHRX = 0x08,
-  CC2420_SFLUSHTX = 0x09,
-  CC2420_SACK = 0x0a,
-  CC2420_SACKPEND = 0x0b,
-  CC2420_SRXDEC = 0x0c,
-  CC2420_SRXENC = 0x0d,
-  CC2420_SAES = 0x0e,
-  CC2420_MAIN = 0x10,
-  CC2420_MDMCTRL0 = 0x11,
-  CC2420_MDMCTRL1 = 0x12,
-  CC2420_RSSI = 0x13,
-  CC2420_SYNCWORD = 0x14,
-  CC2420_TXCTRL = 0x15,
-  CC2420_RXCTRL0 = 0x16,
-  CC2420_RXCTRL1 = 0x17,
-  CC2420_FSCTRL = 0x18,
-  CC2420_SECCTRL0 = 0x19,
-  CC2420_SECCTRL1 = 0x1a,
-  CC2420_BATTMON = 0x1b,
-  CC2420_IOCFG0 = 0x1c,
-  CC2420_IOCFG1 = 0x1d,
-  CC2420_MANFIDL = 0x1e,
-  CC2420_MANFIDH = 0x1f,
-  CC2420_FSMTC = 0x20,
-  CC2420_MANAND = 0x21,
-  CC2420_MANOR = 0x22,
-  CC2420_AGCCTRL = 0x23,
-  CC2420_AGCTST0 = 0x24,
-  CC2420_AGCTST1 = 0x25,
-  CC2420_AGCTST2 = 0x26,
-  CC2420_FSTST0 = 0x27,
-  CC2420_FSTST1 = 0x28,
-  CC2420_FSTST2 = 0x29,
-  CC2420_FSTST3 = 0x2a,
-  CC2420_RXBPFTST = 0x2b,
-  CC2420_FMSTATE = 0x2c,
-  CC2420_ADCTST = 0x2d,
-  CC2420_DACTST = 0x2e,
-  CC2420_TOPTST = 0x2f,
-  CC2420_TXFIFO = 0x3e,
-  CC2420_RXFIFO = 0x3f,
-};
-
-enum cc2420_ram_addr_enums {
-  CC2420_RAM_TXFIFO = 0x000,
-  CC2420_RAM_RXFIFO = 0x080,
-  CC2420_RAM_KEY0 = 0x100,
-  CC2420_RAM_RXNONCE = 0x110,
-  CC2420_RAM_SABUF = 0x120,
-  CC2420_RAM_KEY1 = 0x130,
-  CC2420_RAM_TXNONCE = 0x140,
-  CC2420_RAM_CBCSTATE = 0x150,
-  CC2420_RAM_IEEEADR = 0x160,
-  CC2420_RAM_PANID = 0x168,
-  CC2420_RAM_SHORTADR = 0x16a,
-};
-
-enum cc2420_nonce_enums {
-  CC2420_NONCE_BLOCK_COUNTER = 0,
-  CC2420_NONCE_KEY_SEQ_COUNTER = 2,
-  CC2420_NONCE_FRAME_COUNTER = 3,
-  CC2420_NONCE_SOURCE_ADDRESS = 7,
-  CC2420_NONCE_FLAGS = 15,
-};
-
-enum cc2420_main_enums {
-  CC2420_MAIN_RESETn = 15,
-  CC2420_MAIN_ENC_RESETn = 14,
-  CC2420_MAIN_DEMOD_RESETn = 13,
-  CC2420_MAIN_MOD_RESETn = 12,
-  CC2420_MAIN_FS_RESETn = 11,
-  CC2420_MAIN_XOSC16M_BYPASS = 0,
-};
-
-enum cc2420_mdmctrl0_enums {
-  CC2420_MDMCTRL0_RESERVED_FRAME_MODE = 13,
-  CC2420_MDMCTRL0_PAN_COORDINATOR = 12,
-  CC2420_MDMCTRL0_ADR_DECODE = 11,
-  CC2420_MDMCTRL0_CCA_HYST = 8,
-  CC2420_MDMCTRL0_CCA_MOD = 6,
-  CC2420_MDMCTRL0_AUTOCRC = 5,
-  CC2420_MDMCTRL0_AUTOACK = 4,
-  CC2420_MDMCTRL0_PREAMBLE_LENGTH = 0,
-};
-
-enum cc2420_mdmctrl1_enums {
-  CC2420_MDMCTRL1_CORR_THR = 6,
-  CC2420_MDMCTRL1_DEMOD_AVG_MODE = 5,
-  CC2420_MDMCTRL1_MODULATION_MODE = 4,
-  CC2420_MDMCTRL1_TX_MODE = 2,
-  CC2420_MDMCTRL1_RX_MODE = 0,
-};
-
-enum cc2420_rssi_enums {
-  CC2420_RSSI_CCA_THR = 8,
-  CC2420_RSSI_RSSI_VAL = 0,
-};
-
-enum cc2420_syncword_enums {
-  CC2420_SYNCWORD_SYNCWORD = 0,
-};
-
-enum cc2420_txctrl_enums {
-  CC2420_TXCTRL_TXMIXBUF_CUR = 14,
-  CC2420_TXCTRL_TX_TURNAROUND = 13,
-  CC2420_TXCTRL_TXMIX_CAP_ARRAY = 11,
-  CC2420_TXCTRL_TXMIX_CURRENT = 9,
-  CC2420_TXCTRL_PA_CURRENT = 6,
-  CC2420_TXCTRL_RESERVED = 5,
-  CC2420_TXCTRL_PA_LEVEL = 0,
-};
-
-enum cc2420_rxctrl0_enums {
-  CC2420_RXCTRL0_RXMIXBUF_CUR = 12,
-  CC2420_RXCTRL0_HIGH_LNA_GAIN = 10,
-  CC2420_RXCTRL0_MED_LNA_GAIN = 8,
-  CC2420_RXCTRL0_LOW_LNA_GAIN = 6,
-  CC2420_RXCTRL0_HIGH_LNA_CURRENT = 4,
-  CC2420_RXCTRL0_MED_LNA_CURRENT = 2,
-  CC2420_RXCTRL0_LOW_LNA_CURRENT = 0,
-};
-
-enum cc2420_rxctrl1_enums {
-  CC2420_RXCTRL1_RXBPF_LOCUR = 13,
-  CC2420_RXCTRL1_RXBPF_MIDCUR = 12,
-  CC2420_RXCTRL1_LOW_LOWGAIN = 11,
-  CC2420_RXCTRL1_MED_LOWGAIN = 10,
-  CC2420_RXCTRL1_HIGH_HGM = 9,
-  CC2420_RXCTRL1_MED_HGM = 8,
-  CC2420_RXCTRL1_LNA_CAP_ARRAY = 6,
-  CC2420_RXCTRL1_RXMIX_TAIL = 4,
-  CC2420_RXCTRL1_RXMIX_VCM = 2,
-  CC2420_RXCTRL1_RXMIX_CURRENT = 0,
-};
-
-enum cc2420_rsctrl_enums {
-  CC2420_FSCTRL_LOCK_THR = 14,
-  CC2420_FSCTRL_CAL_DONE = 13,
-  CC2420_FSCTRL_CAL_RUNNING = 12,
-  CC2420_FSCTRL_LOCK_LENGTH = 11,
-  CC2420_FSCTRL_LOCK_STATUS = 10,
-  CC2420_FSCTRL_FREQ = 0,
-};
-
-enum cc2420_secctrl0_enums {
-  CC2420_SECCTRL0_RXFIFO_PROTECTION = 9,
-  CC2420_SECCTRL0_SEC_CBC_HEAD = 8,
-  CC2420_SECCTRL0_SEC_SAKEYSEL = 7,
-  CC2420_SECCTRL0_SEC_TXKEYSEL = 6,
-  CC2420_SECCTRL0_SEC_RXKEYSEL = 5,
-  CC2420_SECCTRL0_SEC_M = 2,
-  CC2420_SECCTRL0_SEC_MODE = 0,
-};
-
-enum cc2420_secctrl1_enums {
-  CC2420_SECCTRL1_SEC_TXL = 8,
-  CC2420_SECCTRL1_SEC_RXL = 0,
-};
-
-enum cc2420_battmon_enums {
-  CC2420_BATTMON_BATT_OK = 6,
-  CC2420_BATTMON_BATTMON_EN = 5,
-  CC2420_BATTMON_BATTMON_VOLTAGE = 0,
-};
-
-enum cc2420_iocfg0_enums {
-  CC2420_IOCFG0_BCN_ACCEPT = 11,
-  CC2420_IOCFG0_FIFO_POLARITY = 10,
-  CC2420_IOCFG0_FIFOP_POLARITY = 9,
-  CC2420_IOCFG0_SFD_POLARITY = 8,
-  CC2420_IOCFG0_CCA_POLARITY = 7,
-  CC2420_IOCFG0_FIFOP_THR = 0,
-};
-
-enum cc2420_iocfg1_enums {
-  CC2420_IOCFG1_HSSD_SRC = 10,
-  CC2420_IOCFG1_SFDMUX = 5,
-  CC2420_IOCFG1_CCAMUX = 0,
-};
-
-enum cc2420_manfidl_enums {
-  CC2420_MANFIDL_PARTNUM = 12,
-  CC2420_MANFIDL_MANFID = 0,
-};
-
-enum cc2420_manfidh_enums {
-  CC2420_MANFIDH_VERSION = 12,
-  CC2420_MANFIDH_PARTNUM = 0,
-};
-
-enum cc2420_fsmtc_enums {
-  CC2420_FSMTC_TC_RXCHAIN2RX = 13,
-  CC2420_FSMTC_TC_SWITCH2TX = 10,
-  CC2420_FSMTC_TC_PAON2TX = 6,
-  CC2420_FSMTC_TC_TXEND2SWITCH = 3,
-  CC2420_FSMTC_TC_TXEND2PAOFF = 0,
-};
-
-enum cc2420_sfdmux_enums {
-  CC2420_SFDMUX_SFD = 0,
-  CC2420_SFDMUX_XOSC16M_STABLE = 24,
-};
-
-#endif
diff --git a/tos/chips/cc2420/CC2420AckLpl.h b/tos/chips/cc2420/CC2420AckLpl.h
deleted file mode 100644 (file)
index 0ff05f0..0000000
+++ /dev/null
@@ -1,102 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS 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
- */
- /**
-  * @author David Moss
-  */
-#ifndef CC2420ACKLPL_H
-#define CC2420ACKLPL_H
-
-/**
- * Low Power Listening Send States
- */
-typedef enum {
-  S_LPL_NOT_SENDING,    // DEFAULT
-  S_LPL_FIRST_MESSAGE,  // 1. Sending the first message
-  S_LPL_SENDING,        // 2. Sending all other messages
-  S_LPL_CLEAN_UP,       // 3. Clean up the transmission
-} lpl_sendstate_t;
-
-
-/**
- * Amount of time, in milliseconds, to keep the radio on after
- * a successful receive addressed to this node
- * You don't want this too fast, or the off timer can accidentally
- * fire due to delays in the system.  The radio would shut off and
- * possibly need to turn back on again immediately, which can lock up
- * the CC2420 if it's in the middle of doing something.
- */
-#ifndef DELAY_AFTER_RECEIVE
-#define DELAY_AFTER_RECEIVE 100
-#endif
-
-/**
- * This is a measured value of the time in ms the radio is actually on
- * We round this up to err on the side of better performance ratios
- */
-#ifndef DUTY_ON_TIME
-#define DUTY_ON_TIME 5 
-#endif
-
-/**
- * The maximum number of CCA checks performed on each wakeup.
- * If there are too few, the receiver may wake up between messages
- * and not detect the transmitter.
- *
- * The on-time had to increase from the original version to allow multiple
- * transmitters to co-exist.  This is due to using ack's, which then requires us
- * to extend the backoff period.  In networks that transmit frequently, possibly
- * with multiple transmitters, this power scheme makes sense.  
- *
- * In networks that transmit very infrequently or without multiple transmitters,
- * it makes more sense to go with no acks and no backoffs and make the
- * receive check as short as possible.
- */
-#ifndef MAX_LPL_CCA_CHECKS
-
-#if defined(PLATFORM_TELOSB) || defined(PLATFORM_TMOTE)
-#define MAX_LPL_CCA_CHECKS 500
-#else
-#define MAX_LPL_CCA_CHECKS 400
-#endif
-
-#endif
-
-/**
- * The minimum number of samples that must be taken in CC2420DutyCycleP
- * that show the channel is not clear before a detection event is issued
- */
-#ifndef MIN_SAMPLES_BEFORE_DETECT
-#define MIN_SAMPLES_BEFORE_DETECT 3
-#endif
-
-#endif
-
diff --git a/tos/chips/cc2420/CC2420AckLplC.nc b/tos/chips/cc2420/CC2420AckLplC.nc
deleted file mode 100644 (file)
index a737bd5..0000000
+++ /dev/null
@@ -1,98 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS 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
- */
-
-/**
- * Low Power Listening for the CC2420
- * @author David Moss
- */
-
-
-#include "CC2420AckLpl.h"
-#warning "*** USING ACK LOW POWER LISTENING LAYER"
-
-configuration CC2420AckLplC {
-  provides {
-    interface LowPowerListening;
-    interface Send;
-    interface Receive;
-    interface SplitControl;
-    interface State as SendState;
-  }
-  
-  uses { 
-    interface Send as SubSend;
-    interface Receive as SubReceive;
-    interface SplitControl as SubControl;
-  }
-}
-
-implementation {
-  components MainC,
-      CC2420AckLplP,
-      CC2420DutyCycleC,
-      CC2420ActiveMessageC,
-      CC2420CsmaC,
-      CC2420TransmitC,
-      CC2420PacketC,
-      RandomC,
-      LedsC,
-      new StateC() as SendStateC,
-      new StateC() as RadioStateC,
-      new TimerMilliC() as OffTimerC,
-      new TimerMilliC() as SendDoneTimerC;
-  
-  LowPowerListening = CC2420AckLplP;
-  Send = CC2420AckLplP;
-  Receive = CC2420AckLplP;
-  SplitControl = CC2420DutyCycleC;
-  SendState = SendStateC;
-  
-  SubControl = CC2420AckLplP.SubControl;
-  SubReceive = CC2420AckLplP.SubReceive;
-  SubSend = CC2420AckLplP.SubSend;
-  
-  
-  MainC.SoftwareInit -> CC2420AckLplP;
-  
-  CC2420AckLplP.Random -> RandomC;
-  CC2420AckLplP.SendState -> SendStateC;
-  CC2420AckLplP.RadioState -> RadioStateC;
-  CC2420AckLplP.SplitControlState -> CC2420DutyCycleC;
-  CC2420AckLplP.OffTimer -> OffTimerC;
-  CC2420AckLplP.SendDoneTimer -> SendDoneTimerC;
-  CC2420AckLplP.CC2420DutyCycle -> CC2420DutyCycleC;
-  CC2420AckLplP.Resend -> CC2420TransmitC;
-  CC2420AckLplP.PacketAcknowledgements -> CC2420ActiveMessageC;
-  CC2420AckLplP.AMPacket -> CC2420ActiveMessageC;
-  CC2420AckLplP.CC2420Packet -> CC2420PacketC;
-  CC2420AckLplP.Leds -> LedsC;
-  
-}
diff --git a/tos/chips/cc2420/CC2420AckLplP.nc b/tos/chips/cc2420/CC2420AckLplP.nc
deleted file mode 100644 (file)
index e35ca47..0000000
+++ /dev/null
@@ -1,509 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS 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
- */
-
-/**
- * Low Power Listening for the CC2420.  This component is responsible for
- * delivery of an LPL packet, and for turning off the radio when the radio
- * has run out of tasks.
- *
- * The CC2420DutyCycle component is responsible for duty cycling the radio
- * and performing receive detections.
- *
- * @author David Moss
- */
-
-#include "CC2420AckLpl.h"
-
-module CC2420AckLplP {
-  provides {
-    interface Init;
-    interface LowPowerListening;
-    interface Send;
-    interface Receive;
-  }
-  
-  uses {
-    interface Send as SubSend;
-    interface CC2420Transmit as Resend;
-    interface Receive as SubReceive;
-    interface AMPacket;
-    interface SplitControl as SubControl;
-    interface CC2420DutyCycle;
-    interface CC2420Packet;
-    interface PacketAcknowledgements;
-    interface State as SendState;
-    interface State as RadioState;
-    interface State as SplitControlState;
-    interface Random;
-    interface Timer<TMilli> as OffTimer;
-    interface Timer<TMilli> as SendDoneTimer;
-    interface Leds;
-  }
-}
-
-implementation {
-  
-  /** The message currently being sent */
-  message_t *currentSendMsg;
-  
-  /** The length of the current send message */
-  uint8_t currentSendLen;
-  
-  /** TRUE if the radio is duty cycling and not always on */
-  bool dutyCycling;
-
-  /**
-   * Radio State
-   */
-  enum {
-    S_OFF,
-    S_ON,
-  };
-  
-  /**
-   * Send States
-   */
-  enum {
-    S_IDLE,
-    S_SENDING,
-  };
-  
-  enum {
-    ONE_MESSAGE = 0,
-  };
-  
-  /***************** Prototypes ***************/
-  task void send();
-  task void resend();
-  task void startRadio();
-  task void stopRadio();
-  
-  void initializeSend();
-  void startOffTimer();
-  uint16_t getActualDutyCycle(uint16_t dutyCycle);
-  
-  /***************** Init Commands ***************/
-  command error_t Init.init() {
-    dutyCycling = FALSE;
-    return SUCCESS;
-  }
-  
-  /***************** LowPowerListening Commands ***************/
-  /**
-   * Set this this node's radio sleep interval, in milliseconds.
-   * Once every interval, the node will sleep and perform an Rx check 
-   * on the radio.  Setting the sleep interval to 0 will keep the radio
-   * always on.
-   *
-   * This is the equivalent of setting the local duty cycle rate.
-   *
-   * @param sleepIntervalMs the length of this node's Rx check interval, in [ms]
-   */
-  command void LowPowerListening.setLocalSleepInterval(
-      uint16_t sleepIntervalMs) {
-    call CC2420DutyCycle.setSleepInterval(sleepIntervalMs);
-  }
-  
-  /**
-   * @return the local node's sleep interval, in [ms]
-   */
-  command uint16_t LowPowerListening.getLocalSleepInterval() {
-    return call CC2420DutyCycle.getSleepInterval();
-  }
-  
-  /**
-   * Set this node's radio duty cycle rate, in units of [percentage*100].
-   * For example, to get a 0.05% duty cycle,
-   * <code>
-   *   call LowPowerListening.setDutyCycle(5);
-   * </code>
-   *
-   * For a 100% duty cycle (always on),
-   * <code>
-   *   call LowPowerListening.setDutyCycle(10000);
-   * </code>
-   *
-   * This is the equivalent of setting the local sleep interval explicitly.
-   * 
-   * @param dutyCycle The duty cycle percentage, in units of [percentage*100]
-   */
-  command void LowPowerListening.setLocalDutyCycle(uint16_t dutyCycle) {
-    call CC2420DutyCycle.setSleepInterval(
-        call LowPowerListening.dutyCycleToSleepInterval(dutyCycle));
-  }
-  
-  /**
-   * @return this node's radio duty cycle rate, in units of [percentage*100]
-   */
-  command uint16_t LowPowerListening.getLocalDutyCycle() {
-    return call LowPowerListening.sleepIntervalToDutyCycle(
-        call CC2420DutyCycle.getSleepInterval());
-  }
-  
-  
-  /**
-   * Configure this outgoing message so it can be transmitted to a neighbor mote
-   * with the specified Rx sleep interval.
-   * @param msg Pointer to the message that will be sent
-   * @param sleepInterval The receiving node's sleep interval, in [ms]
-   */
-  command void LowPowerListening.setRxSleepInterval(message_t *msg, 
-      uint16_t sleepIntervalMs) {
-    (call CC2420Packet.getMetadata(msg))->rxInterval = sleepIntervalMs;
-  }
-  
-  /**
-   * @return the destination node's sleep interval configured in this message
-   */
-  command uint16_t LowPowerListening.getRxSleepInterval(message_t *msg) {
-    return (call CC2420Packet.getMetadata(msg))->rxInterval;
-  }
-  
-  /**
-   * Configure this outgoing message so it can be transmitted to a neighbor mote
-   * with the specified Rx duty cycle rate.
-   * Duty cycle is in units of [percentage*100], i.e. 0.25% duty cycle = 25.
-   * 
-   * @param msg Pointer to the message that will be sent
-   * @param dutyCycle The duty cycle of the receiving mote, in units of 
-   *     [percentage*100]
-   */
-  command void LowPowerListening.setRxDutyCycle(message_t *msg, 
-      uint16_t dutyCycle) {
-    (call CC2420Packet.getMetadata(msg))->rxInterval =
-        call LowPowerListening.dutyCycleToSleepInterval(dutyCycle);
-  }
-  
-    
-  /**
-   * @return the destination node's duty cycle configured in this message
-   *     in units of [percentage*100]
-   */
-  command uint16_t LowPowerListening.getRxDutyCycle(message_t *msg) {
-    return call LowPowerListening.sleepIntervalToDutyCycle(
-        (call CC2420Packet.getMetadata(msg))->rxInterval);
-  }
-  
-  /**
-   * Convert a duty cycle, in units of [percentage*100], to
-   * the sleep interval of the mote in milliseconds
-   * @param dutyCycle The duty cycle in units of [percentage*100]
-   * @return The equivalent sleep interval, in units of [ms]
-   */
-  command uint16_t LowPowerListening.dutyCycleToSleepInterval(
-      uint16_t dutyCycle) {
-    dutyCycle = getActualDutyCycle(dutyCycle);
-    
-    if(dutyCycle == 10000) {
-      return 0;
-    }
-    
-    return (DUTY_ON_TIME * (10000 - dutyCycle)) / dutyCycle;
-  }
-  
-  /**
-   * Convert a sleep interval, in units of [ms], to a duty cycle
-   * in units of [percentage*100]
-   * @param sleepInterval The sleep interval in units of [ms]
-   * @return The duty cycle in units of [percentage*100]
-   */
-  command uint16_t LowPowerListening.sleepIntervalToDutyCycle(
-      uint16_t sleepInterval) {
-    if(sleepInterval == 0) {
-      return 10000;
-    }
-    
-    return getActualDutyCycle((DUTY_ON_TIME * 10000) 
-        / (sleepInterval + DUTY_ON_TIME));
-  }
-
-  
-  /***************** Send Commands ***************/
-  /**
-   * Each call to this send command gives the message a single
-   * DSN that does not change for every copy of the message
-   * sent out.  For messages that are not acknowledged, such as
-   * a broadcast address message, the receiving end does not
-   * signal receive() more than once for that message.
-   */
-  command error_t Send.send(message_t *msg, uint8_t len) {
-    if(call SplitControlState.getState() == S_OFF) {
-      // Everything is off right now, start SplitControl and try again
-      return EOFF;
-    }
-    
-    if(call SendState.requestState(S_LPL_SENDING) == SUCCESS) {
-      currentSendMsg = msg;
-      currentSendLen = len;
-      
-      // In case our off timer is running...
-      call OffTimer.stop();
-      call SendDoneTimer.stop();
-      
-      if(call RadioState.getState() == S_ON) {
-        initializeSend();
-        return SUCCESS;
-        
-      } else {
-        post startRadio();
-      }
-      
-      return SUCCESS;
-    }
-    
-    return FAIL;
-  }
-
-  command error_t Send.cancel(message_t *msg) {
-    if(currentSendMsg == msg) {
-      call SendState.toIdle();
-      call SendDoneTimer.stop();
-      startOffTimer();
-      return call SubSend.cancel(msg);
-    }
-    
-    return FAIL;
-  }
-  
-  
-  command uint8_t Send.maxPayloadLength() {
-    return call SubSend.maxPayloadLength();
-  }
-
-  command void *Send.getPayload(message_t* msg) {
-    return call SubSend.getPayload(msg);
-  }
-  
-  /***************** Receive Commands ***************/
-  command void *Receive.getPayload(message_t* msg, uint8_t* len) {
-    return call SubReceive.getPayload(msg, len);
-  }
-
-  command uint8_t Receive.payloadLength(message_t* msg) {
-    return call SubReceive.payloadLength(msg);
-  }
-
-
-  /***************** DutyCycle Events ***************/
-  /**
-   * A transmitter was detected.  You must now take action to
-   * turn the radio off when the transaction is complete.
-   */
-  event void CC2420DutyCycle.detected() {
-    // At this point, the duty cycling has been disabled temporary
-    // and it will be this component's job to turn the radio back off
-    // Wait long enough to see if we actually receive a packet, which is
-    // just a little longer in case there is more than one lpl transmitter on
-    // the channel.
-    
-    if(call SendState.isIdle()) {
-      startOffTimer();
-    }
-  }
-  
-  
-  /***************** SubControl Events ***************/
-  event void SubControl.startDone(error_t error) {
-    if(!error) {
-      call RadioState.forceState(S_ON);
-      
-      if(call SendState.getState() == S_LPL_FIRST_MESSAGE
-          || call SendState.getState() == S_LPL_SENDING) {
-        initializeSend();
-      }
-    }
-  }
-    
-  event void SubControl.stopDone(error_t error) {
-    if(!error) {
-      call RadioState.forceState(S_OFF);
-
-      if(call SendState.getState() == S_LPL_FIRST_MESSAGE
-          || call SendState.getState() == S_LPL_SENDING) {
-        // We're in the middle of sending a message; start the radio back up
-        post startRadio();
-        
-      } else {        
-        call OffTimer.stop();
-        call SendDoneTimer.stop();
-      }
-    }
-  }
-  
-  /***************** SubSend Events ***************/
-  event void SubSend.sendDone(message_t* msg, error_t error) {
-   
-    switch(call SendState.getState()) {
-    case S_LPL_SENDING:
-      if(call SendDoneTimer.isRunning()) {
-        if(!call PacketAcknowledgements.wasAcked(msg)) {
-          post resend();
-          return;
-        }
-      }
-      break;
-      
-    case S_LPL_CLEAN_UP:
-      /**
-       * We include this state so upper layers can't send a different message
-       * before the last message gets done sending
-       */
-      break;
-      
-    default:
-      break;
-    }  
-    
-    call SendState.toIdle();
-    call SendDoneTimer.stop();
-    startOffTimer();
-    signal Send.sendDone(msg, error);
-  }
-  
-  /***************** SubReceive Events ***************/
-  /**
-   * If the received message is new, we signal the receive event and
-   * start the off timer.  If the last message we received had the same
-   * DSN as this message, then the chances are pretty good
-   * that this message should be ignored, especially if the destination address
-   * as the broadcast address
-   */
-  event message_t *SubReceive.receive(message_t* msg, void* payload, 
-      uint8_t len) {
-    
-    call CC2420DutyCycle.forceDetected();
-    startOffTimer();
-    return signal Receive.receive(msg, payload, len);
-  }
-  
-  /***************** Timer Events ****************/
-  event void OffTimer.fired() {
-    /*
-     * Only stop the radio if the radio is supposed to be off permanently
-     * or if the duty cycle is on and our sleep interval is not 0
-     */
-    if(call SplitControlState.getState() == S_OFF
-        || (call CC2420DutyCycle.getSleepInterval() > 0
-            && call SplitControlState.getState() == S_ON
-                && call SendState.getState() == S_LPL_NOT_SENDING)) { 
-      post stopRadio();
-    }
-  }
-  
-  /**
-   * When this timer is running, that means we're sending repeating messages
-   * to a node that is receive check duty cycling.
-   */
-  event void SendDoneTimer.fired() {
-    if(call SendState.getState() == S_LPL_SENDING) {
-      // The next time SubSend.sendDone is signaled, send is complete.
-      call SendState.forceState(S_LPL_CLEAN_UP);
-    }
-  }
-  
-  /***************** Resend Events ****************/
-  /**
-   * Signal that a message has been sent
-   *
-   * @param p_msg message to send.
-   * @param error notifaction of how the operation went.
-   */
-  async event void Resend.sendDone( message_t* p_msg, error_t error ) {
-    // This is actually caught by SubSend.sendDone
-  }
-  
-  
-  /***************** Tasks ***************/
-  task void send() {
-    if(call SubSend.send(currentSendMsg, currentSendLen) != SUCCESS) {
-      post send();
-    }
-  }
-  
-  task void resend() {
-    if(call Resend.resend(TRUE) != SUCCESS) {
-      post resend();
-    }
-  }
-  
-  task void startRadio() {
-    if(call SubControl.start() != SUCCESS) {
-      post startRadio();
-    }
-  }
-  
-  task void stopRadio() {
-    if(call SendState.getState() == S_LPL_NOT_SENDING) {
-      if(call SubControl.stop() != SUCCESS) {
-        post stopRadio();
-      }
-    }
-  }
-  
-  /***************** Functions ***************/
-  void initializeSend() {
-    if(call LowPowerListening.getRxSleepInterval(currentSendMsg) 
-      > ONE_MESSAGE) {
-    
-      if(call AMPacket.destination(currentSendMsg) == AM_BROADCAST_ADDR) {
-        call PacketAcknowledgements.noAck(currentSendMsg);
-      } else {
-        // Send it repetitively within our transmit window
-        call PacketAcknowledgements.requestAck(currentSendMsg);
-      }
-
-      call SendDoneTimer.startOneShot(
-          call LowPowerListening.getRxSleepInterval(currentSendMsg) + 20);
-    }
-        
-    post send();
-  }
-  
-  
-  void startOffTimer() {
-    call OffTimer.startOneShot(DELAY_AFTER_RECEIVE);
-  }
-  
-  /**
-   * Check the bounds on a given duty cycle
-   * We're never over 100%, and we're never at 0%
-   */
-  uint16_t getActualDutyCycle(uint16_t dutyCycle) {
-    if(dutyCycle > 10000) {
-      return 10000;
-    } else if(dutyCycle == 0) {
-      return 1;
-    }
-    
-    return dutyCycle;
-  }  
-}
-
diff --git a/tos/chips/cc2420/CC2420ActiveMessageC.nc b/tos/chips/cc2420/CC2420ActiveMessageC.nc
deleted file mode 100644 (file)
index e2e7417..0000000
+++ /dev/null
@@ -1,112 +0,0 @@
-/*                                                                     tab:4
- * "Copyright (c) 2005 Stanford University. All rights reserved.
- *
- * Permission to use, copy, modify, and distribute this software and
- * its documentation for any purpose, without fee, and without written
- * agreement is hereby granted, provided that the above copyright
- * notice, the following two paragraphs and the author appear in all
- * copies of this software.
- * 
- * IN NO EVENT SHALL STANFORD UNIVERSITY BE LIABLE TO ANY PARTY FOR
- * DIRECT, INDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES
- * ARISING OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN
- * IF STANFORD UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH
- * DAMAGE.
- * 
- * STANFORD UNIVERSITY SPECIFICALLY DISCLAIMS ANY WARRANTIES,
- * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
- * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.  THE SOFTWARE
- * PROVIDED HEREUNDER IS ON AN "AS IS" BASIS, AND STANFORD UNIVERSITY
- * HAS NO OBLIGATION TO PROVIDE MAINTENANCE, SUPPORT, UPDATES,
- * ENHANCEMENTS, OR MODIFICATIONS."
- */
-
-/**
- * The Active Message layer for the CC2420 radio. This configuration
- * just layers the AM dispatch (CC2420ActiveMessageM) on top of the
- * underlying CC2420 radio packet (CC2420CsmaCsmaCC), which is
- * inherently an AM packet (acknowledgements based on AM destination
- * addr and group). Note that snooping may not work, due to CC2420
- * early packet rejection if acknowledgements are enabled.
- *
- * @author Philip Levis
- * @author David Moss
- * @version $Revision$ $Date$
- */
-
-#include "CC2420.h"
-#include "AM.h"
-
-configuration CC2420ActiveMessageC {
-  provides {
-    interface SplitControl;
-    interface AMSend[am_id_t id];
-    interface Receive[am_id_t id];
-    interface Receive as Snoop[am_id_t id];
-    interface AMPacket;
-    interface Packet;
-    interface CC2420Packet;
-    interface PacketAcknowledgements;
-    interface RadioBackoff[am_id_t amId];
-    interface LowPowerListening;
-    interface PacketLink;
-  }
-}
-implementation {
-
-  components CC2420ActiveMessageP as AM;
-  components CC2420CsmaC as CsmaC;
-  components ActiveMessageAddressC as Address;
-  components UniqueSendC;
-  components UniqueReceiveC;
-  components CC2420TinyosNetworkC;
-  components CC2420PacketC;
-  
-#if defined(LOW_POWER_LISTENING) || defined(ACK_LOW_POWER_LISTENING)
-  components CC2420AckLplC as LplC;
-#elif defined(NOACK_LOW_POWER_LISTENING)
-  components CC2420NoAckLplC as LplC;
-#else
-  components CC2420LplDummyC as LplC;
-#endif
-
-#if defined(PACKET_LINK)
-  components PacketLinkC as LinkC;
-#else
-  components PacketLinkDummyC as LinkC;
-#endif
-
-  
-  RadioBackoff = CsmaC;
-  Packet       = AM;
-  AMSend   = AM;
-  Receive  = AM.Receive;
-  Snoop    = AM.Snoop;
-  AMPacket = AM;
-  PacketLink = LinkC;
-  LowPowerListening = LplC;
-  CC2420Packet = CC2420PacketC;
-  PacketAcknowledgements = CC2420PacketC;
-  
-  
-  // SplitControl Layers
-  SplitControl = LplC;
-  LplC.SubControl -> CsmaC;
-  
-  // Send Layers
-  AM.SubSend -> UniqueSendC;
-  UniqueSendC.SubSend -> LinkC;
-  LinkC.SubSend -> LplC.Send;
-  LplC.SubSend -> CC2420TinyosNetworkC.Send;
-  CC2420TinyosNetworkC.SubSend -> CsmaC;
-  
-  // Receive Layers
-  AM.SubReceive -> LplC;
-  LplC.SubReceive -> UniqueReceiveC.Receive;
-  UniqueReceiveC.SubReceive -> CC2420TinyosNetworkC.Receive;
-  CC2420TinyosNetworkC.SubReceive -> CsmaC;
-
-  AM.amAddress -> Address;
-  AM.CC2420Packet -> CC2420PacketC;
-  
-}
diff --git a/tos/chips/cc2420/CC2420ActiveMessageP.nc b/tos/chips/cc2420/CC2420ActiveMessageP.nc
deleted file mode 100644 (file)
index a4b8625..0000000
+++ /dev/null
@@ -1,202 +0,0 @@
-/*                                                                     tab:4
- * "Copyright (c) 2005 Stanford University. All rights reserved.
- *
- * Permission to use, copy, modify, and distribute this software and
- * its documentation for any purpose, without fee, and without written
- * agreement is hereby granted, provided that the above copyright
- * notice, the following two paragraphs and the author appear in all
- * copies of this software.
- * 
- * IN NO EVENT SHALL STANFORD UNIVERSITY BE LIABLE TO ANY PARTY FOR
- * DIRECT, INDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES
- * ARISING OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN
- * IF STANFORD UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH
- * DAMAGE.
- * 
- * STANFORD UNIVERSITY SPECIFICALLY DISCLAIMS ANY WARRANTIES,
- * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
- * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.  THE SOFTWARE
- * PROVIDED HEREUNDER IS ON AN "AS IS" BASIS, AND STANFORD UNIVERSITY
- * HAS NO OBLIGATION TO PROVIDE MAINTENANCE, SUPPORT, UPDATES,
- * ENHANCEMENTS, OR MODIFICATIONS."
- */
-
-
-/**
- * Active message implementation on top of the CC2420 radio. This
- * implementation uses the 16-bit addressing mode of 802.15.4: the
- * only additional byte it adds is the AM id byte, as the first byte
- * of the data payload.
- *
- * @author Philip Levis
- * @version $Revision$ $Date$
- */
-#include "CC2420.h"
-
-module CC2420ActiveMessageP {
-  provides {
-    interface AMSend[am_id_t id];
-    interface Receive[am_id_t id];
-    interface Receive as Snoop[am_id_t id];
-    interface AMPacket;
-    interface Packet;
-  }
-  uses {
-    interface Send as SubSend;
-    interface Receive as SubReceive;
-    interface CC2420Packet;
-    command am_addr_t amAddress();
-  }
-}
-implementation {
-
-  enum {
-    CC2420_SIZE = MAC_HEADER_SIZE + MAC_FOOTER_SIZE,
-  };
-  
-  
-  command error_t AMSend.send[am_id_t id](am_addr_t addr,
-                                         message_t* msg,
-                                         uint8_t len) {
-    cc2420_header_t* header = call CC2420Packet.getHeader( msg );
-    header->type = id;
-    header->dest = addr;
-    header->destpan = TOS_AM_GROUP;
-
-    return call SubSend.send( msg, len + CC2420_SIZE );
-  }
-
-  command error_t AMSend.cancel[am_id_t id](message_t* msg) {
-    return call SubSend.cancel(msg);
-  }
-
-  command uint8_t AMSend.maxPayloadLength[am_id_t id]() {
-    return call Packet.maxPayloadLength();
-  }
-
-  command void* AMSend.getPayload[am_id_t id](message_t* m) {
-    return call Packet.getPayload(m, NULL);
-  }
-
-  command void* Receive.getPayload[am_id_t id](message_t* m, uint8_t* len) {
-    return call Packet.getPayload(m, len);
-  }
-
-  command uint8_t Receive.payloadLength[am_id_t id](message_t* m) {
-    return call Packet.payloadLength(m);
-  }
-  
-  command void* Snoop.getPayload[am_id_t id](message_t* m, uint8_t* len) {
-    return call Packet.getPayload(m, len);
-  }
-
-  command uint8_t Snoop.payloadLength[am_id_t id](message_t* m) {
-    return call Packet.payloadLength(m);
-  }
-  
-  event void SubSend.sendDone(message_t* msg, error_t result) {
-    signal AMSend.sendDone[call AMPacket.type(msg)](msg, result);
-  }
-
-  /* Receiving a packet */
-
-  event message_t* SubReceive.receive(message_t* msg, void* payload, uint8_t len) {
-    if (call AMPacket.isForMe(msg)) {
-      return signal Receive.receive[call AMPacket.type(msg)](msg, payload, len - CC2420_SIZE);
-    }
-    else {
-      return signal Snoop.receive[call AMPacket.type(msg)](msg, payload, len - CC2420_SIZE);
-    }
-  }
-  
-  command am_addr_t AMPacket.address() {
-    return call amAddress();
-  }
-  command am_addr_t AMPacket.destination(message_t* amsg) {
-    cc2420_header_t* header = call CC2420Packet.getHeader(amsg);
-    return header->dest;
-  }
-  command am_addr_t AMPacket.source(message_t* amsg) {
-    cc2420_header_t* header = call CC2420Packet.getHeader(amsg);
-    return header->src;
-  }
-
-  command void AMPacket.setDestination(message_t* amsg, am_addr_t addr) {
-    cc2420_header_t* header = call CC2420Packet.getHeader(amsg);
-    header->dest = addr;
-  }
-
-  command void AMPacket.setSource(message_t* amsg, am_addr_t addr) {
-    cc2420_header_t* header = call CC2420Packet.getHeader(amsg);
-    header->src = addr;
-  }
-
-  command bool AMPacket.isForMe(message_t* amsg) {
-    return (call AMPacket.destination(amsg) == call AMPacket.address() ||
-           call AMPacket.destination(amsg) == AM_BROADCAST_ADDR);
-  }
-
-  command am_id_t AMPacket.type(message_t* amsg) {
-    cc2420_header_t* header = call CC2420Packet.getHeader(amsg);
-    return header->type;
-  }
-
-  command void AMPacket.setType(message_t* amsg, am_id_t type) {
-    cc2420_header_t* header = call CC2420Packet.getHeader(amsg);
-    header->type = type;
-  }
-
-  command void AMPacket.setGroup(message_t* msg, am_group_t group) {
-    cc2420_header_t* header = call CC2420Packet.getHeader(msg);
-    header->destpan = group;
-  }
-
-  command am_group_t AMPacket.group(message_t* msg) {
-    cc2420_header_t* header = call CC2420Packet.getHeader(msg);
-    return header->destpan;
-  }
-
-  command am_group_t AMPacket.localGroup() {
-    return TOS_AM_GROUP;
-  }
-  
-  default event message_t* Receive.receive[am_id_t id](message_t* msg, void* payload, uint8_t len) {
-    return msg;
-  }
-  
-  default event message_t* Snoop.receive[am_id_t id](message_t* msg, void* payload, uint8_t len) {
-    return msg;
-  }
-
- default event void AMSend.sendDone[uint8_t id](message_t* msg, error_t err) {
-   return;
- }
-
- command void Packet.clear(message_t* msg) {}
- command uint8_t Packet.payloadLength(message_t* msg) {
-   return (call CC2420Packet.getHeader(msg))->length - CC2420_SIZE;
- }
-
-
- command void Packet.setPayloadLength(message_t* msg, uint8_t len) {
-   (call CC2420Packet.getHeader(msg))->length  = len + CC2420_SIZE;
- }
-
- command uint8_t Packet.maxPayloadLength() {
-   return TOSH_DATA_LENGTH;
- }
- command void* Packet.getPayload(message_t* msg, uint8_t* len) {
-   if (len != NULL) {
-     *len = call Packet.payloadLength(msg);
-   }
-   return msg->data;
- }
-
-
-}
diff --git a/tos/chips/cc2420/CC2420Cca.nc b/tos/chips/cc2420/CC2420Cca.nc
deleted file mode 100644 (file)
index 059c9fe..0000000
+++ /dev/null
@@ -1,46 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS 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
- */
-/**
- * Interface to obtain a CCA reading from the CC2420 radio
- * to determine if a neighbor is transmitting
- * @author David Moss
- */
-interface CC2420Cca {
-  
-  /**
-   * @return TRUE if the CCA pin shows a clear channel
-   */
-  command bool isChannelClear();
-  
-}
-
diff --git a/tos/chips/cc2420/CC2420Config.nc b/tos/chips/cc2420/CC2420Config.nc
deleted file mode 100644 (file)
index 90308c3..0000000
+++ /dev/null
@@ -1,73 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Arch Rock Corporation
- * All rights reserved.
- *
- * 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 the Arch Rock Corporation 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
- * ARCHED ROCK OR ITS 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
- */
-
-/**
- * An HAL abstraction of the ChipCon CC2420 radio. This abstraction
- * deals specifically with radio configurations. All get() and set()
- * commands are single-phase. After setting some values, a call to
- * sync() is required for the changes to propagate to the cc2420
- * hardware chip. This interface allows setting multiple parameters
- * before calling sync().
- *
- * @author Jonathan Hui <jhui@archrock.com>
- * @version $Revision$ $Date$
- */
-
-interface CC2420Config {
-
-  /**
-   * Sync configuration changes with the radio hardware. This only
-   * applies to set commands below.
-   *
-   * @return SUCCESS if the request was accepted, FAIL otherwise.
-   */
-  command error_t sync();
-  event void syncDone( error_t error );
-
-  /**
-   * Change the channel of the radio, between 11 and 26
-   */
-  command uint8_t getChannel();
-  command void setChannel( uint8_t channel );
-
-  /**
-   * Change the short address of the radio.
-   */
-  command uint16_t getShortAddr();
-  command void setShortAddr( uint16_t address );
-
-  /**
-   * Change the PAN address of the radio.
-   */
-  command uint16_t getPanAddr();
-  command void setPanAddr( uint16_t address );
-
-}
diff --git a/tos/chips/cc2420/CC2420ControlC.nc b/tos/chips/cc2420/CC2420ControlC.nc
deleted file mode 100644 (file)
index 1657bcf..0000000
+++ /dev/null
@@ -1,98 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Arch Rock Corporation
- * All rights reserved.
- *
- * 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 the Arch Rock Corporation 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
- * ARCHED ROCK OR ITS 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
- */
-
-/**
- * Implementation for configuring a ChipCon CC2420 radio.
- *
- * @author Jonathan Hui <jhui@archrock.com>
- * @version $Revision$ $Date$
- */
-
-#include "CC2420.h"
-#include "IEEE802154.h"
-
-configuration CC2420ControlC {
-
-  provides interface Resource;
-  provides interface CC2420Config;
-  provides interface CC2420Power;
-  provides interface Read<uint16_t> as ReadRssi;
-  
-}
-
-implementation {
-  
-  components CC2420ControlP;
-  Resource = CC2420ControlP;
-  CC2420Config = CC2420ControlP;
-  CC2420Power = CC2420ControlP;
-  ReadRssi = CC2420ControlP;
-
-  components MainC;
-  MainC.SoftwareInit -> CC2420ControlP;
-  
-  components CC2420ActiveMessageC;
-  CC2420ControlP.AMPacket -> CC2420ActiveMessageC;
-  
-  components AlarmMultiplexC as Alarm;
-  CC2420ControlP.StartupTimer -> Alarm;
-
-  components HplCC2420PinsC as Pins;
-  CC2420ControlP.CSN -> Pins.CSN;
-  CC2420ControlP.RSTN -> Pins.RSTN;
-  CC2420ControlP.VREN -> Pins.VREN;
-
-  components HplCC2420InterruptsC as Interrupts;
-  CC2420ControlP.InterruptCCA -> Interrupts.InterruptCCA;
-
-  components new CC2420SpiC() as Spi;
-  CC2420ControlP.SpiResource -> Spi;
-  CC2420ControlP.SRXON -> Spi.SRXON;
-  CC2420ControlP.SRFOFF -> Spi.SRFOFF;
-  CC2420ControlP.SXOSCON -> Spi.SXOSCON;
-  CC2420ControlP.SXOSCOFF -> Spi.SXOSCOFF;
-  CC2420ControlP.FSCTRL -> Spi.FSCTRL;
-  CC2420ControlP.IOCFG0 -> Spi.IOCFG0;
-  CC2420ControlP.IOCFG1 -> Spi.IOCFG1;
-  CC2420ControlP.MDMCTRL0 -> Spi.MDMCTRL0;
-  CC2420ControlP.MDMCTRL1 -> Spi.MDMCTRL1;
-  CC2420ControlP.PANID -> Spi.PANID;
-  CC2420ControlP.RXCTRL1 -> Spi.RXCTRL1;
-  CC2420ControlP.RSSI  -> Spi.RSSI;
-
-  components new CC2420SpiC() as SyncSpiC;
-  CC2420ControlP.SyncResource -> SyncSpiC;
-
-  components new CC2420SpiC() as RssiResource;
-  CC2420ControlP.RssiResource -> RssiResource;
-
-}
-
diff --git a/tos/chips/cc2420/CC2420ControlP.nc b/tos/chips/cc2420/CC2420ControlP.nc
deleted file mode 100644 (file)
index 66d2a80..0000000
+++ /dev/null
@@ -1,358 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Arch Rock Corporation
- * All rights reserved.
- *
- * 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 the Arch Rock Corporation 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
- * ARCHED ROCK OR ITS 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
- */
-
-/**
- * @author Jonathan Hui <jhui@archrock.com>
- * @author Urs Hunkeler (ReadRssi implementation)
- * @version $Revision$ $Date$
- */
-
-#include "Timer.h"
-
-module CC2420ControlP {
-
-  provides interface Init;
-  provides interface Resource;
-  provides interface CC2420Config;
-  provides interface CC2420Power;
-  provides interface Read<uint16_t> as ReadRssi;
-
-  uses interface Alarm<T32khz,uint32_t> as StartupTimer;
-  uses interface GeneralIO as CSN;
-  uses interface GeneralIO as RSTN;
-  uses interface GeneralIO as VREN;
-  uses interface GpioInterrupt as InterruptCCA;
-
-  uses interface CC2420Ram as PANID;
-  uses interface CC2420Register as FSCTRL;
-  uses interface CC2420Register as IOCFG0;
-  uses interface CC2420Register as IOCFG1;
-  uses interface CC2420Register as MDMCTRL0;
-  uses interface CC2420Register as MDMCTRL1;
-  uses interface CC2420Register as RXCTRL1;
-  uses interface CC2420Register as RSSI;
-  uses interface CC2420Strobe as SRXON;
-  uses interface CC2420Strobe as SRFOFF;
-  uses interface CC2420Strobe as SXOSCOFF;
-  uses interface CC2420Strobe as SXOSCON;
-  uses interface AMPacket;
-  
-  uses interface Resource as SpiResource;
-  uses interface Resource as RssiResource;
-  uses interface Resource as SyncResource;
-
-  uses interface Leds;
-
-}
-
-implementation {
-
-  typedef enum {
-    S_VREG_STOPPED,
-    S_VREG_STARTING,
-    S_VREG_STARTED,
-    S_XOSC_STARTING,
-    S_XOSC_STARTED,
-  } cc2420_control_state_t;
-
-  uint8_t m_channel = CC2420_DEF_CHANNEL;
-  
-  uint8_t m_tx_power = CC2420_DEF_RFPOWER;
-  
-  uint16_t m_pan = TOS_AM_GROUP;
-  
-  uint16_t m_short_addr;
-  
-  bool m_sync_busy;
-  
-  norace cc2420_control_state_t m_state = S_VREG_STOPPED;
-  
-  /***************** Prototypes ****************/
-  task void syncDone_task();
-
-  /***************** Init Commands ****************/
-  command error_t Init.init() {
-    call CSN.makeOutput();
-    call RSTN.makeOutput();
-    call VREN.makeOutput();
-    m_short_addr = call AMPacket.address();
-    return SUCCESS;
-  }
-
-  /***************** Resource Commands ****************/
-  async command error_t Resource.immediateRequest() {
-    error_t error = call SpiResource.immediateRequest();
-    if ( error == SUCCESS ) {
-      call CSN.clr();
-    }
-    return error;
-  }
-
-  async command error_t Resource.request() {
-    return call SpiResource.request();
-  }
-
-  async command uint8_t Resource.isOwner() {
-    return call SpiResource.isOwner();
-  }
-
-  async command error_t Resource.release() {
-    atomic {
-      call CSN.set();
-      return call SpiResource.release();
-    }
-  }
-
-  /***************** CC2420Power Commands ****************/
-  async command error_t CC2420Power.startVReg() {
-    atomic {
-      if ( m_state != S_VREG_STOPPED ) {
-        return FAIL;
-      }
-      m_state = S_VREG_STARTING;
-    }
-    call VREN.set();
-    call StartupTimer.start( CC2420_TIME_VREN );
-    return SUCCESS;
-  }
-
-  async command error_t CC2420Power.stopVReg() {
-    m_state = S_VREG_STOPPED;
-    call RSTN.clr();
-    call VREN.clr();
-    call RSTN.set();
-    return SUCCESS;
-  }
-
-  async command error_t CC2420Power.startOscillator() {
-    atomic {
-      if ( m_state != S_VREG_STARTED ) {
-        return FAIL;
-      }
-        
-      m_state = S_XOSC_STARTING;
-      call IOCFG1.write( CC2420_SFDMUX_XOSC16M_STABLE << 
-                         CC2420_IOCFG1_CCAMUX );
-                         
-      call InterruptCCA.enableRisingEdge();
-      call SXOSCON.strobe();
-      
-      call IOCFG0.write( ( 1 << CC2420_IOCFG0_FIFOP_POLARITY ) |
-                         ( 127 << CC2420_IOCFG0_FIFOP_THR ) );
-                         
-      call FSCTRL.write( ( 1 << CC2420_FSCTRL_LOCK_THR ) |
-                         ( ( (m_channel - 11)*5+357 ) 
-                           << CC2420_FSCTRL_FREQ ) );
-                           
-      call MDMCTRL0.write( ( 1 << CC2420_MDMCTRL0_RESERVED_FRAME_MODE ) |
-                           ( 1 << CC2420_MDMCTRL0_ADR_DECODE ) |
-                           ( 2 << CC2420_MDMCTRL0_CCA_HYST ) |
-                           ( 3 << CC2420_MDMCTRL0_CCA_MOD ) |
-                           ( 1 << CC2420_MDMCTRL0_AUTOCRC ) |
-#if defined(CC2420_HW_ACKNOWLEDGEMENTS) && !defined(CC2420_NO_ACKNOWLEDGEMENTS)
-                           ( 1 << CC2420_MDMCTRL0_AUTOACK ) |
-#else
-                           ( 0 << CC2420_MDMCTRL0_AUTOACK ) |
-#endif
-                           ( 2 << CC2420_MDMCTRL0_PREAMBLE_LENGTH ) );
-                           
-      call RXCTRL1.write( ( 1 << CC2420_RXCTRL1_RXBPF_LOCUR ) |
-                          ( 1 << CC2420_RXCTRL1_LOW_LOWGAIN ) |
-                          ( 1 << CC2420_RXCTRL1_HIGH_HGM ) |
-                          ( 1 << CC2420_RXCTRL1_LNA_CAP_ARRAY ) |
-                          ( 1 << CC2420_RXCTRL1_RXMIX_TAIL ) |
-                          ( 1 << CC2420_RXCTRL1_RXMIX_VCM ) |
-                          ( 2 << CC2420_RXCTRL1_RXMIX_CURRENT ) );
-    }
-    return SUCCESS;
-  }
-
-
-  async command error_t CC2420Power.stopOscillator() {
-    atomic {
-      if ( m_state != S_XOSC_STARTED ) {
-        return FAIL;
-      }
-      m_state = S_VREG_STARTED;
-      call SXOSCOFF.strobe();
-    }
-    return SUCCESS;
-  }
-
-  async command error_t CC2420Power.rxOn() {
-    atomic {
-      if ( m_state != S_XOSC_STARTED ) {
-        return FAIL;
-      }
-      call SRXON.strobe();
-    }
-    return SUCCESS;
-  }
-
-  async command error_t CC2420Power.rfOff() {
-    atomic {  
-      if ( m_state != S_XOSC_STARTED ) {
-        return FAIL;
-      }
-      call SRFOFF.strobe();
-    }
-    return SUCCESS;
-  }
-
-  
-  /***************** CC2420Config Commands ****************/
-  command uint8_t CC2420Config.getChannel() {
-    atomic return m_channel;
-  }
-
-  command void CC2420Config.setChannel( uint8_t channel ) {
-    atomic m_channel = channel;
-  }
-
-  command uint16_t CC2420Config.getShortAddr() {
-    atomic return m_short_addr;
-  }
-
-  command void CC2420Config.setShortAddr( uint16_t addr ) {
-    atomic m_short_addr = addr;
-  }
-
-  command uint16_t CC2420Config.getPanAddr() {
-    return m_pan;
-  }
-
-  command void CC2420Config.setPanAddr( uint16_t pan ) {
-    atomic m_pan = pan;
-  }
-
-  command error_t CC2420Config.sync() {
-    atomic {
-      if ( m_sync_busy ) {
-        return FAIL;
-      }
-      
-      m_sync_busy = TRUE;
-      if ( m_state == S_XOSC_STARTED ) {
-        call SyncResource.request();
-      } else {
-        post syncDone_task();
-      }
-    }
-    return SUCCESS;
-  }
-
-  /***************** ReadRssi Commands ****************/
-  command error_t ReadRssi.read() { 
-    return call RssiResource.request();
-  }
-  
-  /***************** Spi Resources Events ****************/
-  event void SyncResource.granted() {
-
-    nxle_uint16_t id[ 2 ];
-    uint8_t channel;
-
-    atomic {
-      channel = m_channel;
-      id[ 0 ] = m_pan;
-      id[ 1 ] = m_short_addr;
-    }
-
-    call CSN.clr();
-    call SRFOFF.strobe();
-    call FSCTRL.write( ( 1 << CC2420_FSCTRL_LOCK_THR ) |
-                       ( ( (channel - 11)*5+357 ) << CC2420_FSCTRL_FREQ ) );
-    call PANID.write( 0, (uint8_t*)id, sizeof( id ) );
-    call CSN.set();
-    call CSN.clr();
-    call SRXON.strobe();
-    call CSN.set();
-    call SyncResource.release();
-    
-    post syncDone_task();
-    
-  }
-
-  event void SpiResource.granted() {
-    call CSN.clr();
-    signal Resource.granted();
-  }
-
-  event void RssiResource.granted() { 
-    uint16_t data;
-    call CSN.clr();
-    call RSSI.read(&data);
-    call CSN.set();
-    
-    call RssiResource.release();
-    data += 0x7f;
-    data &= 0x00ff;
-    signal ReadRssi.readDone(SUCCESS, data); 
-  }
-  
-  /***************** StartupTimer Events ****************/
-  async event void StartupTimer.fired() {
-    if ( m_state == S_VREG_STARTING ) {
-      m_state = S_VREG_STARTED;
-      call RSTN.clr();
-      call RSTN.set();
-      signal CC2420Power.startVRegDone();
-    }
-  }
-
-  /***************** InterruptCCA Events ****************/
-  async event void InterruptCCA.fired() {
-    nxle_uint16_t id[ 2 ];
-    m_state = S_XOSC_STARTED;
-    id[ 0 ] = m_pan;
-    id[ 1 ] = m_short_addr;
-    call InterruptCCA.disable();
-    call IOCFG1.write( 0 );
-    call PANID.write( 0, (uint8_t*)&id, 4 );
-    call CSN.set();
-    call CSN.clr();
-    signal CC2420Power.startOscillatorDone();
-  }
-  
-  /***************** Tasks ****************/
-  task void syncDone_task() {
-    atomic m_sync_busy = FALSE;
-    signal CC2420Config.syncDone( SUCCESS );
-  }
-
-  /***************** Defaults ****************/
-  default event void CC2420Config.syncDone( error_t error ) {
-  }
-
-  default event void ReadRssi.readDone(error_t error, uint16_t data) {
-  }
-  
-}
diff --git a/tos/chips/cc2420/CC2420CsmaC.nc b/tos/chips/cc2420/CC2420CsmaC.nc
deleted file mode 100644 (file)
index d6d2e57..0000000
+++ /dev/null
@@ -1,89 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Arch Rock Corporation
- * All rights reserved.
- *
- * 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 the Arch Rock Corporation 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
- * ARCHED ROCK OR ITS 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
- */
-
-/**
- * Basic implementation of a CSMA MAC for the ChipCon CC2420 radio.
- *
- * @author Jonathan Hui <jhui@archrock.com>
- * @version $Revision$ $Date$
- */
-
-#include "CC2420.h"
-#include "IEEE802154.h"
-
-configuration CC2420CsmaC {
-
-  provides interface SplitControl;
-  provides interface Send;
-  provides interface Receive;
-  provides interface RadioBackoff[am_id_t amId];
-
-}
-
-implementation {
-
-  components CC2420CsmaP as CsmaP;
-  RadioBackoff = CsmaP;
-  SplitControl = CsmaP;
-  Send = CsmaP;
-
-  components MainC;
-  MainC.SoftwareInit -> CsmaP;
-  
-  components CC2420SpiP;
-  CsmaP.SpiSplitControl -> CC2420SpiP;
-  
-  components CC2420ActiveMessageC;
-  CsmaP.AMPacket -> CC2420ActiveMessageC;
-  
-  components CC2420ControlC;
-  CsmaP.Resource -> CC2420ControlC;
-  CsmaP.CC2420Power -> CC2420ControlC;
-
-  components CC2420TransmitC;
-  CsmaP.SubControl -> CC2420TransmitC;
-  CsmaP.CC2420Transmit -> CC2420TransmitC;
-  CsmaP.SubBackoff -> CC2420TransmitC;
-
-  components CC2420ReceiveC;
-  Receive = CC2420ReceiveC;
-  CsmaP.SubControl -> CC2420ReceiveC;
-
-  components CC2420PacketC;
-  CsmaP.CC2420Packet -> CC2420PacketC;
-  
-  components RandomC;
-  CsmaP.Random -> RandomC;
-
-  components LedsC as Leds;
-  CsmaP.Leds -> Leds;
-  
-}
diff --git a/tos/chips/cc2420/CC2420CsmaP.nc b/tos/chips/cc2420/CC2420CsmaP.nc
deleted file mode 100644 (file)
index 9c77335..0000000
+++ /dev/null
@@ -1,303 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Arch Rock Corporation
- * All rights reserved.
- *
- * 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 the Arch Rock Corporation 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
- * ARCHED ROCK OR ITS 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
- */
-
-/**
- * @author Jonathan Hui <jhui@archrock.com>
- * @version $Revision$ $Date$
- */
-
-module CC2420CsmaP {
-
-  provides interface Init;
-  provides interface SplitControl;
-  provides interface Send;
-  provides interface RadioBackoff[am_id_t amId];
-
-  uses interface Resource;
-  uses interface CC2420Power;
-  uses interface SplitControl as SpiSplitControl;
-  uses interface StdControl as SubControl;
-  uses interface CC2420Transmit;
-  uses interface RadioBackoff as SubBackoff;
-  uses interface Random;
-  uses interface AMPacket;
-  uses interface Leds;
-  uses interface CC2420Packet;
-
-}
-
-implementation {
-
-  enum {
-    S_PREINIT,
-    S_STOPPED,
-    S_STARTING,
-    S_STARTED,
-    S_STOPPING,
-    S_TRANSMIT,
-  };
-
-  message_t* m_msg;
-  
-  uint8_t m_state = S_PREINIT;
-  
-  error_t sendErr = SUCCESS;
-  
-  /** TRUE if we are to use CCA when sending the current packet */
-  norace bool ccaOn;
-  
-  /****************** Prototypes ****************/
-  task void startDone_task();
-  task void startDone_task();
-  task void stopDone_task();
-  task void sendDone_task();
-
-  /***************** Init Commands ****************/
-  command error_t Init.init() {
-    if ( m_state != S_PREINIT ) {
-      return FAIL;
-    }
-    m_state = S_STOPPED;
-    return SUCCESS;
-  }
-
-  /***************** SplitControl Commands ****************/
-  command error_t SplitControl.start() {
-    if ( m_state != S_STOPPED ) {
-      return FAIL;
-    }
-
-    m_state = S_STARTING;
-    call SpiSplitControl.start();
-    // Wait for SpiSplitControl.startDone()
-    return SUCCESS;
-  }
-
-  command error_t SplitControl.stop() {
-    if ( m_state != S_STARTED ) {
-      return FAIL;
-    }
-
-    m_state = S_STOPPING;
-    call SpiSplitControl.stop();
-    // Wait for SpiSplitControl.stopDone()
-    return SUCCESS;
-  }
-
-  /***************** SpiSplitControl Events ****************/
-  event void SpiSplitControl.startDone(error_t error) {
-    call CC2420Power.startVReg();
-  }
-  
-  event void SpiSplitControl.stopDone(error_t error) {
-    call SubControl.stop();
-    call CC2420Power.stopVReg();
-    post stopDone_task();
-  }
-    
-  /***************** Send Commands ****************/
-  command error_t Send.cancel( message_t* p_msg ) {
-    return call CC2420Transmit.cancel();
-  }
-
-  command error_t Send.send( message_t* p_msg, uint8_t len ) {
-    
-    cc2420_header_t* header = call CC2420Packet.getHeader( p_msg );
-    cc2420_metadata_t* metadata = call CC2420Packet.getMetadata( p_msg );
-
-    atomic {
-      if ( m_state != S_STARTED ) {
-        return FAIL;
-      }
-      m_state = S_TRANSMIT;
-      m_msg = p_msg;
-    }
-
-    header->length = len;
-    header->fcf &= 1 << IEEE154_FCF_ACK_REQ;
-    header->fcf |= ( ( IEEE154_TYPE_DATA << IEEE154_FCF_FRAME_TYPE ) |
-                    ( 1 << IEEE154_FCF_INTRAPAN ) |
-                    ( IEEE154_ADDR_SHORT << IEEE154_FCF_DEST_ADDR_MODE ) |
-                    ( IEEE154_ADDR_SHORT << IEEE154_FCF_SRC_ADDR_MODE ) );
-    header->src = call AMPacket.address();
-    metadata->ack = FALSE;
-    metadata->rssi = 0;
-    metadata->lqi = 0;
-    metadata->time = 0;
-    
-    ccaOn = TRUE;
-    signal RadioBackoff.requestCca[((cc2420_header_t*)(m_msg->data - 
-        sizeof(cc2420_header_t)))->type](m_msg);
-    call CC2420Transmit.send( m_msg, ccaOn );
-    return SUCCESS;
-
-  }
-
-  command void* Send.getPayload(message_t* m) {
-    return m->data;
-  }
-
-  command uint8_t Send.maxPayloadLength() {
-    return TOSH_DATA_LENGTH;
-  }
-
-  /**************** RadioBackoff Commands ****************/
-  /**
-   * Must be called within a requestInitialBackoff event
-   * @param backoffTime the amount of time in some unspecified units to backoff
-   */
-  async command void RadioBackoff.setInitialBackoff[am_id_t amId](uint16_t backoffTime) {
-    call SubBackoff.setInitialBackoff(backoffTime);
-  }
-  
-  /**
-   * Must be called within a requestCongestionBackoff event
-   * @param backoffTime the amount of time in some unspecified units to backoff
-   */
-  async command void RadioBackoff.setCongestionBackoff[am_id_t amId](uint16_t backoffTime) {
-    call SubBackoff.setCongestionBackoff(backoffTime);
-  }
-  
-  /**
-   * Must be called within a requestLplBackoff event
-   * @param backoffTime the amount of time in some unspecified units to backoff
-   */
-  async command void RadioBackoff.setLplBackoff[am_id_t amId](uint16_t backoffTime) {
-    call SubBackoff.setLplBackoff(backoffTime);
-  }
-    
-  /**
-   * Enable CCA for the outbound packet.  Must be called within a requestCca
-   * event
-   * @param ccaOn TRUE to enable CCA, which is the default.
-   */
-  async command void RadioBackoff.setCca[am_id_t amId](bool useCca) {
-    ccaOn = useCca;
-  }
-  
-
-  /**************** Events ****************/
-  async event void CC2420Transmit.sendDone( message_t* p_msg, error_t err ) {
-    atomic sendErr = err;
-    post sendDone_task();
-  }
-
-  async event void CC2420Power.startVRegDone() {
-    call Resource.request();
-  }
-  
-  event void Resource.granted() {
-    call CC2420Power.startOscillator();
-  }
-
-  async event void CC2420Power.startOscillatorDone() {
-    post startDone_task();
-  }
-  
-  /***************** SubBackoff Events ****************/
-  async event void SubBackoff.requestInitialBackoff(message_t *msg) {
-    call SubBackoff.setInitialBackoff ( call Random.rand16() 
-        % (0x1F * CC2420_BACKOFF_PERIOD) + CC2420_MIN_BACKOFF);
-        
-    signal RadioBackoff.requestInitialBackoff[((cc2420_header_t*)(msg->data - 
-        sizeof(cc2420_header_t)))->type](msg);
-  }
-
-  async event void SubBackoff.requestCongestionBackoff(message_t *msg) {
-    call SubBackoff.setCongestionBackoff( call Random.rand16() 
-        % (0x7 * CC2420_BACKOFF_PERIOD) + CC2420_MIN_BACKOFF);
-
-    signal RadioBackoff.requestCongestionBackoff[((cc2420_header_t*)(msg->data - 
-        sizeof(cc2420_header_t)))->type](msg);
-  }
-  
-  async event void SubBackoff.requestLplBackoff(message_t *msg) {
-    call SubBackoff.setLplBackoff(call Random.rand16() % 10);
-        
-    signal RadioBackoff.requestLplBackoff[((cc2420_header_t*)(msg->data - 
-        sizeof(cc2420_header_t)))->type](msg);
-  }
-  
-  async event void SubBackoff.requestCca(message_t *msg) {
-    // Lower layers than this do not configure the CCA settings
-  }
-  
-  
-  /***************** Tasks ****************/
-  task void sendDone_task() {
-    error_t packetErr;
-    atomic packetErr = sendErr;
-    m_state = S_STARTED;
-    signal Send.sendDone( m_msg, packetErr );
-  }
-
-  task void startDone_task() {
-    call SubControl.start();
-    call CC2420Power.rxOn();
-    call Resource.release();
-    m_state = S_STARTED;
-    signal SplitControl.startDone( SUCCESS );
-  }
-  
-  task void stopDone_task() {
-    m_state = S_STOPPED;
-    signal SplitControl.stopDone( SUCCESS );
-  }
-  
-  
-  /***************** Functions ****************/
-
-
-  /***************** Defaults ***************/
-  default event void SplitControl.startDone(error_t error) {
-  }
-  
-  default event void SplitControl.stopDone(error_t error) {
-  }
-  
-  
-  default async event void RadioBackoff.requestInitialBackoff[am_id_t amId](
-      message_t *msg) {
-  }
-
-  default async event void RadioBackoff.requestCongestionBackoff[am_id_t amId](
-      message_t *msg) {
-  }
-  
-  default async event void RadioBackoff.requestLplBackoff[am_id_t amId](
-      message_t *msg) {
-  }
-  
-  default async event void RadioBackoff.requestCca[am_id_t amId](
-      message_t *msg) {
-  }
-}
-
diff --git a/tos/chips/cc2420/CC2420DutyCycle.nc b/tos/chips/cc2420/CC2420DutyCycle.nc
deleted file mode 100644 (file)
index 30c75f3..0000000
+++ /dev/null
@@ -1,67 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS 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
- */
-/**
- * Manage the CC2420's duty cycle and power
- * @author David Moss
- */
-interface CC2420DutyCycle {
-  
-  /**
-   * Set the sleep interval, in binary milliseconds
-   * @param sleepIntervalMs the sleep interval in [ms]
-   */
-  command void setSleepInterval(uint16_t sleepIntervalMs);
-  
-  /**
-   * @return the sleep interval in [ms]
-   */
-  command uint16_t getSleepInterval();
-  
-  /**
-   * Sometimes the radio kicks on and an Rx interrupt causes the CCA
-   * checking for-loop to stop doing its job.  The upper layers receive
-   * a message, but the for-loop CCA check never got the detect because it
-   * got cut off.  So, LPL can override the duty cycler and leave the radio in 
-   * its current state. When the radio turns back off again, the duty cycling 
-   * continues
-   */
-  command void forceDetected();
-  
-  /**
-   * A transmitter was detected.  You must now take action to
-   * turn the radio off when the transaction is complete.
-   */
-  event void detected();
-
-}
-
diff --git a/tos/chips/cc2420/CC2420DutyCycleC.nc b/tos/chips/cc2420/CC2420DutyCycleC.nc
deleted file mode 100644 (file)
index 1c7ec37..0000000
+++ /dev/null
@@ -1,88 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS 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
- */
-/**
- * Use this component to duty cycle the radio. When a message is heard, 
- * disable DutyCycling.
- *
- * @author David Moss dmm@rincon.com
- */
-
-configuration CC2420DutyCycleC {
-  provides {
-    interface CC2420DutyCycle;
-    interface SplitControl;
-    interface State as SplitControlState;
-  }
-}
-
-implementation {
-  components MainC,
-      CC2420DutyCycleP,
-      CC2420TransmitC,
-      CC2420CsmaC,
-      LedsC,
-      new StateC() as RadioPowerStateC,
-      new StateC() as DutyCycleStateC,
-      new StateC() as CheckStateC,
-      new StateC() as SplitControlStateC,
-      new TimerMilliC() as OnTimerC,
-      new TimerMilliC() as CheckTimerC,
-      RandomC;
-
-#if defined(LOW_POWER_LISTENING) || defined(ACK_LOW_POWER_LISTENING)
-  components CC2420AckLplC as LplC;
-#elif defined(NOACK_LOW_POWER_LISTENING)
-  components CC2420NoAckLplC as LplC;
-#else
-  components CC2420LplDummyC as LplC;
-#endif
-
-  CC2420DutyCycle = CC2420DutyCycleP;
-  SplitControl = CC2420DutyCycleP;
-  SplitControlState = SplitControlStateC;
-  
-  MainC.SoftwareInit -> CC2420DutyCycleP;
-  
-  CC2420DutyCycleP.Random -> RandomC;
-  CC2420DutyCycleP.CC2420Cca -> CC2420TransmitC;
-  CC2420DutyCycleP.SubControl -> CC2420CsmaC;
-  CC2420DutyCycleP.SendState -> LplC;
-  CC2420DutyCycleP.RadioPowerState -> RadioPowerStateC;
-  CC2420DutyCycleP.DutyCycleState -> DutyCycleStateC;
-  CC2420DutyCycleP.SplitControlState -> SplitControlStateC;
-  CC2420DutyCycleP.CheckState -> CheckStateC;
-  CC2420DutyCycleP.OnTimer -> OnTimerC;
-  CC2420DutyCycleP.Leds -> LedsC;
-    
-}
-
-
diff --git a/tos/chips/cc2420/CC2420DutyCycleP.nc b/tos/chips/cc2420/CC2420DutyCycleP.nc
deleted file mode 100644 (file)
index 6162b60..0000000
+++ /dev/null
@@ -1,311 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS 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
- */
-/** 
- * Module to duty cycle the radio on and off, performing CCA receive checks.
- * When a carrier is sensed, this will leave the radio on. It is then up
- * to higher layers to turn the radio off again.  Once the radio is turned
- * off, this module will automatically continue duty cycling and looking for
- * a modulated signal.
- *
- * @author David Moss
- */
-module CC2420DutyCycleP {
-  provides {
-    interface CC2420DutyCycle;
-    interface Init;
-    interface SplitControl;
-  }
-
-  uses {
-    interface Timer<TMilli> as OnTimer;
-    interface SplitControl as SubControl;
-    interface State as RadioPowerState;
-    interface State as DutyCycleState;
-    interface State as SplitControlState;
-    interface State as CheckState;
-    interface State as SendState;
-    interface Leds;
-    interface CC2420Cca;
-    interface Random;
-  }
-}
-
-implementation {
-  
-  /** The current period of the duty cycle, equivalent of wakeup interval */
-  uint16_t sleepInterval;
-  
-  /** The number of times the CCA has been sampled in this wakeup period */
-  uint16_t ccaChecks;
-  
-  /** TRUE if we get an Rx interrupt that stops our CCA checking loop */
-  bool detectionForced;
-  
-  /**
-   * Radio Power, Check State, and Duty Cycling State
-   */
-  enum {
-    S_OFF, // off by default
-    S_ON,
-  };
-  
-  
-  /***************** Prototypes ****************/
-  task void stopRadio();
-  task void startRadio();
-  task void getCca();
-  
-  /***************** Init Commands ****************/
-  command error_t Init.init() {
-    sleepInterval = 0;
-   return SUCCESS;
-  }
-  
-  /***************** CC2420DutyCycle Commands ****************/
-  /**
-   * Set the sleep interval, in binary milliseconds
-   * @param sleepIntervalMs the sleep interval in [ms]
-   */
-  command void CC2420DutyCycle.setSleepInterval(uint16_t sleepIntervalMs) {
-    if (!sleepInterval && sleepIntervalMs) {
-      // We were always on, now lets duty cycle
-      call DutyCycleState.forceState(S_ON);
-      call CheckState.toIdle();
-      post stopRadio();  // Might want to delay turning off the radio
-    }
-    
-    detectionForced = FALSE;
-    sleepInterval = sleepIntervalMs;
-    
-    if(sleepInterval == 0 && call DutyCycleState.getState() == S_ON) {
-      call DutyCycleState.forceState(S_OFF);
-      call CheckState.toIdle();
-      
-      /*
-       * Leave the radio on permanently if sleepInterval == 0 and the radio is 
-       * supposed to be enabled
-       */
-      if(call RadioPowerState.getState() == S_OFF) {
-        call SubControl.start();
-      }
-    }
-  }
-  
-  /**
-   * @return the sleep interval in [ms]
-   */
-  command uint16_t CC2420DutyCycle.getSleepInterval() {
-    return sleepInterval;
-  }
-  
-  command void CC2420DutyCycle.forceDetected() {
-    detectionForced = TRUE;
-  }
-  
-  /***************** SplitControl Commands ****************/
-  command error_t SplitControl.start() {
-    call SplitControlState.forceState(S_ON);
-    
-    if(sleepInterval > 0) {
-      // Begin duty cycling
-      call DutyCycleState.forceState(S_ON);
-      call CheckState.toIdle();
-      post stopRadio();
-      signal SplitControl.startDone(SUCCESS);
-      
-    } else {
-      call DutyCycleState.forceState(S_OFF);
-      call CheckState.toIdle();
-      
-      /*
-       * Leave the radio on permanently if sleepInterval == 0 and the radio is 
-       * supposed to be enabled
-       */
-      if(call RadioPowerState.getState() == S_OFF) {
-        call SubControl.start();
-        // Here, SplitControl.startDone is signaled on SubControl.startDone
-        
-      } else {
-        // Radio is already on
-        signal SplitControl.startDone(SUCCESS);
-      }
-    }
-
-    return SUCCESS;
-  }
-  
-  command error_t SplitControl.stop() {
-    call SplitControlState.forceState(S_OFF);
-    call DutyCycleState.forceState(S_OFF);
-    call CheckState.toIdle();
-    return call SubControl.stop();
-    
-    /*
-     * SubControl.stopDone signals SplitControl.stopDone when  
-     * DutyCycleState is S_OFF
-     */
-  }
-  
-  /***************** Timer Events ****************/
-  event void OnTimer.fired() {
-    if(call DutyCycleState.getState() == S_ON) {
-      if(call RadioPowerState.getState() == S_OFF) {
-        call CheckState.forceState(S_ON);
-        ccaChecks = 0;
-        
-        /*
-         * The MicaZ, running on an external oscillator I think, and
-         * returning the microcontroller out of a sleep state to immediately
-         * perform an ADC conversion, sucks.  The first ADC conversion out
-         * of a sleep state lasts about a second.  We don't want the radio
-         * on that long.  Like the CC1000 RSSI pulse check implementation
-         * done in the Rincon CC1000Radio stack, we will perform
-         * a single ADC conversion and then flip on the radio to check
-         * the channel.
-         */
-         post getCca();
-        
-      } else {
-        // Someone else turned on the radio, try again in awhile
-        call OnTimer.startOneShot(sleepInterval);
-      }
-    }
-  }
-  
-  /***************** SubControl Events ****************/
-  event void SubControl.startDone(error_t error) {
-    if(call DutyCycleState.getState() == S_ON && error) {
-      // My responsibility to try again
-      post startRadio();
-      return;
-    }
-    
-    call RadioPowerState.forceState(S_ON);
-    //call Leds.led2On();
-    
-    if(call DutyCycleState.getState() == S_ON) {
-      if(call CheckState.getState() == S_ON) {
-        post getCca();
-      }
-      
-    } else {
-      // Must have turned the radio on manually
-      signal SplitControl.startDone(SUCCESS);
-    }
-  }
-  
-  event void SubControl.stopDone(error_t error) {
-    if(error && call DutyCycleState.getState() == S_ON) {
-      // My responsibility to try again
-      post stopRadio();
-      return;
-    }
-    
-    detectionForced = FALSE;
-    call RadioPowerState.forceState(S_OFF);
-    //call Leds.led2Off();
-    
-    if(call DutyCycleState.getState() == S_ON) {
-      call OnTimer.startOneShot(sleepInterval);
-
-    } else {
-      // Must have turned off the radio manually
-      signal SplitControl.stopDone(error);
-    }
-    
-  }
-  
-  
-  /***************** Tasks ****************/
-  task void stopRadio() {
-    if(call DutyCycleState.getState() == S_ON && !detectionForced) {
-      if(call SubControl.stop() != SUCCESS) {
-        // Already stopped?
-        call OnTimer.startOneShot(sleepInterval);
-      }
-    }
-  }
-  
-  task void startRadio() {
-    if(call DutyCycleState.getState() == S_ON) {
-      if(call SubControl.start() != SUCCESS) {
-        post startRadio();
-      }
-    }
-  }
-  
-  task void getCca() {
-    uint8_t detects = 0;
-    if(call DutyCycleState.getState() == S_ON) {
-      
-      ccaChecks++;
-      if(ccaChecks == 1) {
-        // Microcontroller is ready, turn on the radio and sample a few times
-        post startRadio();
-        return;
-      }
-
-      atomic {
-        for( ; ccaChecks < MAX_LPL_CCA_CHECKS && call SendState.isIdle(); ccaChecks++) {
-          if(!call CC2420Cca.isChannelClear() || detectionForced) {
-            detects++;
-            if(detects > MIN_SAMPLES_BEFORE_DETECT) {
-              signal CC2420DutyCycle.detected(); 
-              return;
-            }
-            // Leave the radio on for upper layers to perform some transaction
-          }
-        }
-      }
-      
-      call CheckState.toIdle();
-      if(call SendState.isIdle()) {
-        post stopRadio();
-      }
-    }  
-  }
-  
-  /**************** Defaults ****************/
-  default event void CC2420DutyCycle.detected() {
-  }
-
-
-  default event void SplitControl.startDone(error_t error) {
-  }
-  
-  default event void SplitControl.stopDone(error_t error) {
-  }
-}
-
-
diff --git a/tos/chips/cc2420/CC2420Fifo.nc b/tos/chips/cc2420/CC2420Fifo.nc
deleted file mode 100644 (file)
index 115a0d3..0000000
+++ /dev/null
@@ -1,93 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Arch Rock Corporation
- * All rights reserved.
- *
- * 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 the Arch Rock Corporation 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
- * ARCHED ROCK OR ITS 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
- */
-
-/**
- * HAL abstraction for accessing the FIFO registers of a ChipCon
- * CC2420 radio.
- *
- * @author Jonathan Hui <jhui@archrock.com>
- * @version $Revision$ $Date$
- */
-
-interface CC2420Fifo {
-
-  /**
-   * Start reading from the FIFO. The <code>readDone</code> event will
-   * be signalled upon completion.
-   *
-   * @param data a pointer to the receive buffer.
-   * @param length number of bytes to read.
-   * @return status byte returned when sending the last address byte
-   * of the SPI transaction.
-   */
-  async command cc2420_status_t beginRead( uint8_t* data, uint8_t length );
-
-  /**
-   * Continue reading from the FIFO without having to send the address
-   * byte again. The <code>readDone</code> event will be signalled
-   * upon completion.
-   *
-   * @param data a pointer to the receive buffer.
-   * @param length number of bytes to read.
-   * @return SUCCESS always.
-   */
-  async command error_t continueRead( uint8_t* data, uint8_t length );
-
-  /**
-   * Signals the completion of a read operation.
-   *
-   * @param data a pointer to the receive buffer.
-   * @param length number of bytes read.
-   * @param error notification of how the operation went
-   */
-  async event void readDone( uint8_t* data, uint8_t length, error_t error );
-
-  /**
-   * Start writing the FIFO. The <code>writeDone</code> event will be
-   * signalled upon completion.
-   *
-   * @param data a pointer to the send buffer.
-   * @param length number of bytes to write.
-   * @return status byte returned when sending the last address byte
-   * of the SPI transaction.
-   */
-  async command cc2420_status_t write( uint8_t* data, uint8_t length );
-
-  /**
-   * Signals the completion of a write operation.
-   *
-   * @param data a pointer to the send buffer.
-   * @param length number of bytes written.
-   * @param error notification of how the operation went
-   */
-  async event void writeDone( uint8_t* data, uint8_t length, error_t error );
-
-}
diff --git a/tos/chips/cc2420/CC2420LplDummyC.nc b/tos/chips/cc2420/CC2420LplDummyC.nc
deleted file mode 100644 (file)
index b8ef1e6..0000000
+++ /dev/null
@@ -1,66 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS 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
- */
-/**
- * Dummy low power listening interface used when LowPowerListening is not
- * compiled in with the application.
- * Sleep interval is always 0, and duty cycle is always 100%
- * @author David Moss
- */
-configuration CC2420LplDummyC {
-  provides {
-    interface Send;
-    interface Receive;
-    interface LowPowerListening;
-    interface SplitControl;
-    interface State as SendState;
-  }
-  
-  uses {
-    interface Send as SubSend;
-    interface Receive as SubReceive;
-    interface SplitControl as SubControl;
-  }
-}
-
-implementation {
-  components CC2420LplDummyP;
-  components new StateC();
-  
-  Send = SubSend;
-  Receive = SubReceive;
-  SplitControl = SubControl;
-  LowPowerListening = CC2420LplDummyP;
-  SendState = StateC;
-  
-}
-
diff --git a/tos/chips/cc2420/CC2420LplDummyP.nc b/tos/chips/cc2420/CC2420LplDummyP.nc
deleted file mode 100644 (file)
index 97bdd0c..0000000
+++ /dev/null
@@ -1,84 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS 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
- */
-/**
- * Dummy low power listening interface used when LowPowerListening is not
- * compiled in with the application.
- * Sleep interval is always 0, and duty cycle is always 100%
- * @author David Moss
- */
-module CC2420LplDummyP {
-  provides {
-    interface LowPowerListening;
-  }
-}
-
-implementation {
-
-  command void LowPowerListening.setLocalSleepInterval(uint16_t sleepIntervalMs) {
-  }
-  
-  command uint16_t LowPowerListening.getLocalSleepInterval() {
-    return 0;
-  }
-  
-  command void LowPowerListening.setLocalDutyCycle(uint16_t dutyCycle) {
-  }
-  
-  command uint16_t LowPowerListening.getLocalDutyCycle() {
-    return 10000;
-  }
-  
-  command void LowPowerListening.setRxSleepInterval(message_t *msg, uint16_t sleepIntervalMs) {
-  }
-  
-  command uint16_t LowPowerListening.getRxSleepInterval(message_t *msg) {
-    return 0;
-  }
-  
-  command void LowPowerListening.setRxDutyCycle(message_t *msg, uint16_t dutyCycle) {
-  }
-  
-  command uint16_t LowPowerListening.getRxDutyCycle(message_t *msg) {
-    return 10000;
-  }
-  
-  command uint16_t LowPowerListening.dutyCycleToSleepInterval(uint16_t dutyCycle) {
-    return 0;
-  }
-  
-  command uint16_t LowPowerListening.sleepIntervalToDutyCycle(uint16_t sleepInterval) {
-    return 10000;
-  }
-  
-}
-
diff --git a/tos/chips/cc2420/CC2420NoAckLpl.h b/tos/chips/cc2420/CC2420NoAckLpl.h
deleted file mode 100644 (file)
index 7d00c50..0000000
+++ /dev/null
@@ -1,97 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS 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
- */
- /**
-  * @author David Moss
-  */
-#ifndef CC2420NOACKLPL_H
-#define CC2420NOACKLPL_H
-
-/**
- * Low Power Listening Send States
- */
-typedef enum {
-  S_LPL_NOT_SENDING,    // DEFAULT
-  S_LPL_FIRST_MESSAGE,  // 1. Initial backoffs, no acks, full CCA
-  S_LPL_LAST_MESSAGE,   // 3. No backoffs, acknowledgement request, no CCA
-} lpl_sendstate_t;
-
-/**
- * Amount of time, in milliseconds, to keep the radio on after
- * a successful receive addressed to this node
- * You don't want this too fast, or the off timer can accidentally
- * fire due to delays in the system.  The radio would shut off and
- * possibly need to turn back on again immediately, which can lock up
- * the CC2420 if it's in the middle of doing something.
- */
-#ifndef DELAY_AFTER_RECEIVE
-#define DELAY_AFTER_RECEIVE 100
-#endif
-
-
-/**
- * This is a measured value of the time in ms the radio is actually on
- * We round this up to err on the side of better performance ratios
- */
-#ifndef DUTY_ON_TIME
-#define DUTY_ON_TIME 1
-#endif
-
-/**
- * The maximum number of CCA checks performed on each wakeup.
- * The value is relative to the speed of transmission and speed of the
- * microcontroller executing the receive check loop. If the transmission
- * is ultimately back-to-back without break or the microcontroller
- * is slow, we can do less samples. If the microcontroller is very 
- * fast, we must do more samples.  Keep in mind the datasheet also
- * specifies that the CCA pin is valid after 8 symbol periods of
- * the radio being on.
- */
-#ifndef MAX_LPL_CCA_CHECKS
-
-#if defined(PLATFORM_TELOSB)
-#define MAX_LPL_CCA_CHECKS 12
-#else
-#define MAX_LPL_CCA_CHECKS 12
-#endif
-
-#endif
-
-/**
- * The minimum number of samples that must be taken in CC2420DutyCycleP
- * that show the channel is not clear before a detection event is issued
- */
-#ifndef MIN_SAMPLES_BEFORE_DETECT
-#define MIN_SAMPLES_BEFORE_DETECT 1
-#endif
-
-#endif
-
diff --git a/tos/chips/cc2420/CC2420NoAckLplC.nc b/tos/chips/cc2420/CC2420NoAckLplC.nc
deleted file mode 100644 (file)
index e733b98..0000000
+++ /dev/null
@@ -1,109 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS 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
- */
-
-/**
- * Low Power Listening for the CC2420
- * This is experimental because:
- *  > Acknowledgements really don't work at all, even on the last message
- *    which is supposed to return an acknowledgement from the receiver.
- *  > The CRC is not yet manually calculated, so the entire continuous
- *    modulation doesn't contain any useful information.
- *    By adding in the CRC calcuation functionality to TransmitP,
- *    we can better support mobile nodes that walk out of range and
- *    lossy connections.  We could also put receivers back to sleep that
- *    the "preamble" is not destined for, because the actual preamble
- *    would have an address associated with it.
- *
- * @author David Moss
- */
-#include "CC2420NoAckLpl.h"
-#warning "*** USING EXPERIMENTAL NO-ACK LOW POWER LISTENING LAYER"
-
-configuration CC2420NoAckLplC {
-  provides {
-    interface LowPowerListening;
-    interface Send;
-    interface Receive;
-    interface SplitControl;
-    interface State as SendState;
-  }
-  
-  uses { 
-    interface Send as SubSend;
-    interface Receive as SubReceive;
-    interface SplitControl as SubControl;
-  }
-}
-
-implementation {
-  components MainC,
-      CC2420NoAckLplP,
-      CC2420DutyCycleC,
-      CC2420ActiveMessageC,
-      CC2420CsmaC,
-      CC2420TransmitC,
-      CC2420PacketC,
-      RandomC,
-      LedsC,
-      new StateC() as SendStateC,
-      new StateC() as RadioStateC,
-      new TimerMilliC() as OffTimerC;
-  
-  LowPowerListening = CC2420NoAckLplP;
-  Send = CC2420NoAckLplP;
-  Receive = CC2420NoAckLplP;
-  SplitControl = CC2420DutyCycleC;
-  SendState = SendStateC;
-  
-  SubControl = CC2420NoAckLplP.SubControl;
-  SubReceive = CC2420NoAckLplP.SubReceive;
-  SubSend = CC2420NoAckLplP.SubSend;
-  
-  
-  MainC.SoftwareInit -> CC2420NoAckLplP;
-  
-  CC2420NoAckLplP.Random -> RandomC;
-  CC2420NoAckLplP.SendState -> SendStateC;
-  CC2420NoAckLplP.RadioState -> RadioStateC;
-  CC2420NoAckLplP.SplitControlState -> CC2420DutyCycleC;
-  CC2420NoAckLplP.CC2420Cca -> CC2420TransmitC;
-  CC2420NoAckLplP.OffTimer -> OffTimerC;
-  CC2420NoAckLplP.CC2420DutyCycle -> CC2420DutyCycleC;
-  CC2420NoAckLplP.Resend -> CC2420TransmitC;
-  CC2420NoAckLplP.PacketAcknowledgements -> CC2420ActiveMessageC;
-  CC2420NoAckLplP.AMPacket -> CC2420ActiveMessageC;
-  CC2420NoAckLplP.CC2420Packet -> CC2420PacketC;
-  CC2420NoAckLplP.RadioBackoff -> CC2420CsmaC;
-  CC2420NoAckLplP.Leds -> LedsC;
-  
-}
-
diff --git a/tos/chips/cc2420/CC2420NoAckLplP.nc b/tos/chips/cc2420/CC2420NoAckLplP.nc
deleted file mode 100644 (file)
index 8657af1..0000000
+++ /dev/null
@@ -1,552 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS 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
- */
-
-/**
- * Low Power Listening for the CC2420.  This component is responsible for
- * delivery of an LPL packet, and for turning off the radio when the radio
- * has run out of tasks.
- *
- * The CC2420DutyCycle component is responsible for duty cycling the radio
- * and performing receive detections.
- *
- * @author David Moss
- */
-
-#include "CC2420NoAckLpl.h"
-
-module CC2420NoAckLplP {
-  provides {
-    interface Init;
-    interface LowPowerListening;
-    interface Send;
-    interface Receive;
-  }
-  
-  uses {
-    interface Send as SubSend;
-    interface CC2420Transmit as Resend;
-    interface Receive as SubReceive;
-    interface AMPacket;
-    interface CC2420Cca;
-    interface SplitControl as SubControl;
-    interface CC2420DutyCycle;
-    interface CC2420Packet;
-    interface PacketAcknowledgements;
-    interface RadioBackoff[am_id_t amId];
-    interface State as SendState;
-    interface State as RadioState;
-    interface State as SplitControlState;
-    interface Random;
-    interface Timer<TMilli> as OffTimer;
-    interface Leds;
-  }
-}
-
-implementation {
-  
-  /** The message currently being sent */
-  message_t *currentSendMsg;
-  
-  /** The length of the current send message */
-  uint8_t currentSendLen;
-  
-  /** TRUE if the radio is duty cycling and not always on */
-  bool dutyCycling;
-  
-  /** TRUE if we have received a message after the last detect */
-  bool receivedMsg;
-  
-  
-  /**
-   * Radio State
-   */
-  enum {
-    S_OFF,
-    S_ON,
-  };
-  
-  /**
-   * Send States
-   */
-  enum {
-    S_IDLE,
-    S_SENDING,
-  };
-  
-  enum {
-    ONE_MESSAGE = 0,
-  };
-  
-  
-  /***************** Prototypes ***************/
-  task void send();
-  task void resend();
-  task void startRadio();
-  task void stopRadio();
-  task void detectTxDone();
-  
-  void initializeSend();
-  void startOffTimer();
-  uint16_t getActualDutyCycle(uint16_t dutyCycle);
-  
-  /***************** Init Commands ***************/
-  command error_t Init.init() {
-    dutyCycling = FALSE;
-    return SUCCESS;
-  }
-  
-  /***************** LowPowerListening Commands ***************/
-  /**
-   * Set this this node's radio sleep interval, in milliseconds.
-   * Once every interval, the node will sleep and perform an Rx check 
-   * on the radio.  Setting the sleep interval to 0 will keep the radio
-   * always on.
-   *
-   * This is the equivalent of setting the local duty cycle rate.
-   *
-   * @param sleepIntervalMs the length of this node's Rx check interval, in [ms]
-   */
-  command void LowPowerListening.setLocalSleepInterval(
-      uint16_t sleepIntervalMs) {
-    call CC2420DutyCycle.setSleepInterval(sleepIntervalMs);
-  }
-  
-  /**
-   * @return the local node's sleep interval, in [ms]
-   */
-  command uint16_t LowPowerListening.getLocalSleepInterval() {
-    return call CC2420DutyCycle.getSleepInterval();
-  }
-  
-  /**
-   * Set this node's radio duty cycle rate, in units of [percentage*100].
-   * For example, to get a 0.05% duty cycle,
-   * <code>
-   *   call LowPowerListening.setDutyCycle(5);
-   * </code>
-   *
-   * For a 100% duty cycle (always on),
-   * <code>
-   *   call LowPowerListening.setDutyCycle(10000);
-   * </code>
-   *
-   * This is the equivalent of setting the local sleep interval explicitly.
-   * 
-   * @param dutyCycle The duty cycle percentage, in units of [percentage*100]
-   */
-  command void LowPowerListening.setLocalDutyCycle(uint16_t dutyCycle) {
-    call CC2420DutyCycle.setSleepInterval(
-        call LowPowerListening.dutyCycleToSleepInterval(dutyCycle));
-  }
-  
-  /**
-   * @return this node's radio duty cycle rate, in units of [percentage*100]
-   */
-  command uint16_t LowPowerListening.getLocalDutyCycle() {
-    return call LowPowerListening.sleepIntervalToDutyCycle(
-        call CC2420DutyCycle.getSleepInterval());
-  }
-  
-  
-  /**
-   * Configure this outgoing message so it can be transmitted to a neighbor mote
-   * with the specified Rx sleep interval.
-   * @param msg Pointer to the message that will be sent
-   * @param sleepInterval The receiving node's sleep interval, in [ms]
-   */
-  command void LowPowerListening.setRxSleepInterval(message_t *msg, 
-      uint16_t sleepIntervalMs) {
-    (call CC2420Packet.getMetadata(msg))->rxInterval = sleepIntervalMs;
-  }
-  
-  /**
-   * @return the destination node's sleep interval configured in this message
-   */
-  command uint16_t LowPowerListening.getRxSleepInterval(message_t *msg) {
-    return (call CC2420Packet.getMetadata(msg))->rxInterval;
-  }
-  
-  /**
-   * Configure this outgoing message so it can be transmitted to a neighbor mote
-   * with the specified Rx duty cycle rate.
-   * Duty cycle is in units of [percentage*100], i.e. 0.25% duty cycle = 25.
-   * 
-   * @param msg Pointer to the message that will be sent
-   * @param dutyCycle The duty cycle of the receiving mote, in units of 
-   *     [percentage*100]
-   */
-  command void LowPowerListening.setRxDutyCycle(message_t *msg, 
-      uint16_t dutyCycle) {
-    (call CC2420Packet.getMetadata(msg))->rxInterval =
-        call LowPowerListening.dutyCycleToSleepInterval(dutyCycle);
-  }
-  
-    
-  /**
-   * @return the destination node's duty cycle configured in this message
-   *     in units of [percentage*100]
-   */
-  command uint16_t LowPowerListening.getRxDutyCycle(message_t *msg) {
-    return call LowPowerListening.sleepIntervalToDutyCycle(
-        (call CC2420Packet.getMetadata(msg))->rxInterval);
-  }
-  
-  /**
-   * Convert a duty cycle, in units of [percentage*100], to
-   * the sleep interval of the mote in milliseconds
-   * @param dutyCycle The duty cycle in units of [percentage*100]
-   * @return The equivalent sleep interval, in units of [ms]
-   */
-  command uint16_t LowPowerListening.dutyCycleToSleepInterval(
-      uint16_t dutyCycle) {
-    dutyCycle = getActualDutyCycle(dutyCycle);
-    
-    if(dutyCycle == 10000) {
-      return 0;
-    }
-    
-    return (DUTY_ON_TIME * (10000 - dutyCycle)) / dutyCycle;
-  }
-  
-  /**
-   * Convert a sleep interval, in units of [ms], to a duty cycle
-   * in units of [percentage*100]
-   * @param sleepInterval The sleep interval in units of [ms]
-   * @return The duty cycle in units of [percentage*100]
-   */
-  command uint16_t LowPowerListening.sleepIntervalToDutyCycle(
-      uint16_t sleepInterval) {
-    if(sleepInterval == 0) {
-      return 10000;
-    }
-    
-    return getActualDutyCycle((DUTY_ON_TIME * 10000) 
-        / (sleepInterval + DUTY_ON_TIME));
-  }
-
-  
-  /***************** Send Commands ***************/
-  /**
-   * Each call to this send command gives the message a single
-   * DSN that does not change for every copy of the message
-   * sent out.  For messages that are not acknowledged, such as
-   * a broadcast address message, the receiving end does not
-   * signal receive() more than once for that message.
-   */
-  command error_t Send.send(message_t *msg, uint8_t len) {
-    if(call SplitControlState.getState() == S_OFF) {
-      // Everything is off right now, start SplitControl and try again
-      return EOFF;
-    }
-    
-    if(call SendState.requestState(S_LPL_FIRST_MESSAGE) == SUCCESS) {
-      currentSendMsg = msg;
-      currentSendLen = len;
-      
-      // In case our off timer is running...
-      call OffTimer.stop();
-      
-      if(call RadioState.getState() == S_ON) {
-        initializeSend();
-        return SUCCESS;
-        
-      } else {
-        post startRadio();
-      }
-      
-      return SUCCESS;
-    }
-    
-    return FAIL;
-  }
-
-  command error_t Send.cancel(message_t *msg) {
-    if(currentSendMsg == msg) {
-      call SendState.toIdle();
-      startOffTimer();
-      return call SubSend.cancel(msg);
-    }
-    
-    return FAIL;
-  }
-  
-  
-  command uint8_t Send.maxPayloadLength() {
-    return call SubSend.maxPayloadLength();
-  }
-
-  command void *Send.getPayload(message_t* msg) {
-    return call SubSend.getPayload(msg);
-  }
-  
-  /***************** Receive Commands ***************/
-  command void *Receive.getPayload(message_t* msg, uint8_t* len) {
-    return call SubReceive.getPayload(msg, len);
-  }
-
-  command uint8_t Receive.payloadLength(message_t* msg) {
-    return call SubReceive.payloadLength(msg);
-  }
-
-
-  /***************** DutyCycle Events ***************/
-  /**
-   * A transmitter was detected.  You must now take action to
-   * turn the radio off when the transaction is complete.
-   */
-  event void CC2420DutyCycle.detected() {
-    // At this point, the duty cycling has been disabled temporary
-    // and it will be this component's job to turn the radio back off
-    // Wait long enough to see if we actually receive a packet
-    receivedMsg = FALSE;
-    post detectTxDone();
-  }
-  
-  
-  /***************** SubControl Events ***************/
-  event void SubControl.startDone(error_t error) {
-    if(!error) {
-      call RadioState.forceState(S_ON);
-      
-      if(call SendState.getState() == S_LPL_FIRST_MESSAGE) {
-        initializeSend();
-      }
-    }
-  }
-  
-  event void SubControl.stopDone(error_t error) {
-    if(!error) {
-      call RadioState.forceState(S_OFF);
-
-      if(call SendState.getState() == S_LPL_FIRST_MESSAGE) {
-        // We're in the middle of sending a message; start the radio back up
-        post startRadio();
-        
-      } else {
-        call OffTimer.stop();
-      }
-    }
-  }
-  
-  /***************** SubSend Events ***************/
-  event void SubSend.sendDone(message_t* msg, error_t error) {
-    switch(call SendState.getState()) {
-    case S_LPL_FIRST_MESSAGE:
-      call SendState.forceState(S_LPL_LAST_MESSAGE);
-      call PacketAcknowledgements.requestAck(msg);
-      post send();
-      return;
-    
-    case S_LPL_LAST_MESSAGE:
-      // Execute past the switch statement
-      break;
-      
-    default:
-      // Execute past the switch statement
-      break;
-    }
-    
-    call SendState.toIdle();
-    startOffTimer();
-    signal Send.sendDone(msg, error);
-  }
-  
-  /***************** SubReceive Events ***************/
-  /**
-   * If the received message is new, we signal the receive event and
-   * start the off timer.  If the last message we received had the same
-   * DSN as this message, then the chances are pretty good
-   * that this message should be ignored, especially if the destination address
-   * as the broadcast address
-   */
-  event message_t *SubReceive.receive(message_t* msg, void* payload, 
-      uint8_t len) {
-    
-    /**
-     * Now wait for the next moment the channel is free before passing the 
-     * packet up, and keep the radio on that whole time.  That's when our
-     * transmitter is done transmitting, LPL or not.
-     */
-    
-    call CC2420DutyCycle.forceDetected();
-    receivedMsg = TRUE;
-    startOffTimer();
-    return signal Receive.receive(msg, payload, len);
-  }
-  
-  /***************** Timer Events ****************/
-  event void OffTimer.fired() {
-    /*
-     * Only stop the radio if the radio is supposed to be off permanently
-     * or if the duty cycle is on and our sleep interval is not 0
-     */
-    if(call SplitControlState.getState() == S_OFF
-        || (call CC2420DutyCycle.getSleepInterval() > 0
-            && call SplitControlState.getState() == S_ON
-                && call SendState.getState() == S_LPL_NOT_SENDING)) { 
-      post stopRadio();
-    }
-  }
-  
-  /***************** RadioBackoff Events ****************/
-  /**  
-   * Request for input on the initial backoff
-   * Reply using setInitialBackoff(..)
-   * @param msg pointer to the message being sent
-   */
-  async event void RadioBackoff.requestInitialBackoff[am_id_t amId](message_t *msg) {
-  }
-  
-  /**
-   * Request for input on the congestion backoff
-   * Reply using setCongestionBackoff(..)
-   * @param msg pointer to the message being sent
-   */
-  async event void RadioBackoff.requestCongestionBackoff[am_id_t amId](message_t *msg) {
-  }
-  
-  /**
-   * Request for input on the low power listening backoff
-   * This should be somewhat random, but as short as possible
-   * Reply using setLplBackoff(..)
-   * @param msg pointer to the message being sent
-   */
-  async event void RadioBackoff.requestLplBackoff[am_id_t amId](message_t *msg) {
-  }
-  
-  /**
-   * Request for input on whether or not to use CCA on the outbound packet.
-   * Replies should come in the form of setCca(..)
-   * @param msg pointer to the message being sent
-   */
-  async event void RadioBackoff.requestCca[am_id_t amId](message_t *msg) {
-    if(call SendState.getState() == S_LPL_FIRST_MESSAGE) {
-      call RadioBackoff.setCca[amId](TRUE);
-
-    } else if(call SendState.getState() == S_LPL_LAST_MESSAGE) {
-      call RadioBackoff.setCca[amId](FALSE);
-    }
-  }
-  
-  
-  /***************** Resend Events ****************/
-  /**
-   * Signal that a message has been sent
-   *
-   * @param p_msg message to send.
-   * @param error notifaction of how the operation went.
-   */
-  async event void Resend.sendDone( message_t* p_msg, error_t error ) {
-    // This is actually caught by SubSend.sendDone
-  }
-  
-  
-  /***************** Tasks ***************/
-  task void send() {
-    if(call SubSend.send(currentSendMsg, currentSendLen) != SUCCESS) {
-      post send();
-    }
-  }
-  
-  task void resend() {
-    if(call Resend.resend(FALSE) != SUCCESS) {
-      post resend();
-    }
-  }
-  
-  task void startRadio() {
-    if(call SubControl.start() != SUCCESS) {
-      post startRadio();
-    }
-  }
-  
-  task void stopRadio() {
-    if(call SendState.getState() == S_LPL_NOT_SENDING) {
-      if(call SubControl.stop() != SUCCESS) {
-        post stopRadio();
-      }
-    }
-  }
-  
-  /**
-   * Don't start the off-timer until the end of the transmitter's transmission.
-   */
-  task void detectTxDone() {
-    uint16_t clearChannelSamples;
-    
-    if(call SendState.getState() != S_LPL_FIRST_MESSAGE
-        && call SendState.getState() != S_LPL_LAST_MESSAGE
-        && !receivedMsg) {
-      for(clearChannelSamples = 0; clearChannelSamples < MAX_LPL_CCA_CHECKS * 8; clearChannelSamples++) {
-        // In one straight shot, sample the channel repetitively and verify that
-        // the transmitter is done transmitting
-        if(!call CC2420Cca.isChannelClear()) {
-          // Nope, start over from the beginning.
-          post detectTxDone();
-          return;
-        }
-      }
-
-      // Transmitter done, turn the radio off in a few...
-      startOffTimer();
-    }
-  }
-  
-  /***************** Functions ***************/
-  void initializeSend() {
-    if(call LowPowerListening.getRxSleepInterval(currentSendMsg) 
-        > ONE_MESSAGE) {
-      call PacketAcknowledgements.noAck(currentSendMsg);
-    }
-    
-    post send();
-  }
-  
-  
-  void startOffTimer() {
-    call OffTimer.startOneShot(DELAY_AFTER_RECEIVE);
-  }
-  
-  /**
-   * Check the bounds on a given duty cycle
-   * We're never over 100%, and we're never at 0%
-   */
-  uint16_t getActualDutyCycle(uint16_t dutyCycle) {
-    if(dutyCycle > 10000) {
-      return 10000;
-    } else if(dutyCycle == 0) {
-      return 1;
-    }
-    
-    return dutyCycle;
-  }  
-}
-
diff --git a/tos/chips/cc2420/CC2420Packet.nc b/tos/chips/cc2420/CC2420Packet.nc
deleted file mode 100644 (file)
index 2c95597..0000000
+++ /dev/null
@@ -1,83 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Arch Rock Corporation
- * All rights reserved.
- *
- * 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 the Arch Rock Corporation 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
- * ARCHED ROCK OR ITS 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
- */
-
-/**
- * @author Jonathan Hui <jhui@archrock.com>
- * @author David Moss
- * @author Chad Metcalf
- */
-
-#include "message.h"
-
-interface CC2420Packet {
-  
-  /**
-   * Get transmission power setting for current packet.
-   *
-   * @param the message
-   */
-  async command uint8_t getPower( message_t* p_msg );
-
-  /**
-   * Set transmission power for a given packet. Valid ranges are
-   * between 0 and 31.
-   *
-   * @param p_msg the message.
-   * @param power transmission power.
-   */
-  async command void setPower( message_t* p_msg, uint8_t power );
-  
-  /**
-   * Get rssi value for a given packet. For received packets, it is
-   * the received signal strength when receiving that packet. For sent
-   * packets, it is the received signal strength of the ack if an ack
-   * was received.
-   */
-  async command int8_t getRssi( message_t* p_msg );
-
-  /**
-   * Get lqi value for a given packet. For received packets, it is the
-   * link quality indicator value when receiving that packet. For sent
-   * packets, it is the link quality indicator value of the ack if an
-   * ack was received.
-   */
-  async command uint8_t getLqi( message_t* p_msg );
-  
-  /**
-   * @return pointer to the cc2420_header_t of the given message
-   */
-  async command cc2420_header_t *getHeader(message_t *msg);
-  
-  /**
-   * @return pointer to the cc2420_metadata_t of the given message
-   */
-  async command cc2420_metadata_t *getMetadata(message_t *msg);
-}
diff --git a/tos/chips/cc2420/CC2420PacketC.nc b/tos/chips/cc2420/CC2420PacketC.nc
deleted file mode 100644 (file)
index 9241185..0000000
+++ /dev/null
@@ -1,90 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Arch Rock Corporation
- * All rights reserved.
- *
- * 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 the Arch Rock Corporation 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
- * ARCHED ROCK OR ITS 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
- */
-
-/**
- * @author Jonathan Hui <jhui@archrock.com>
- * @author David Moss
- * @author Chad Metcalf
- */
-
-#include "IEEE802154.h"
-#include "message.h"
-
-module CC2420PacketC {
-
-  provides interface CC2420Packet;
-  provides interface PacketAcknowledgements as Acks;
-
-}
-
-implementation {
-
-  async command cc2420_header_t *CC2420Packet.getHeader( message_t* msg ) {
-    return (cc2420_header_t*)( msg->data - sizeof( cc2420_header_t ) );
-  }
-
-  async command cc2420_metadata_t *CC2420Packet.getMetadata( message_t* msg ) {
-    return (cc2420_metadata_t*)msg->metadata;
-  }
-
-  async command error_t Acks.requestAck( message_t* p_msg ) {
-    (call CC2420Packet.getHeader( p_msg ))->fcf |= 1 << IEEE154_FCF_ACK_REQ;
-    return SUCCESS;
-  }
-
-  async command error_t Acks.noAck( message_t* p_msg ) {
-    (call CC2420Packet.getHeader( p_msg ))->fcf &= ~(1 << IEEE154_FCF_ACK_REQ);
-    return SUCCESS;
-  }
-
-  async command bool Acks.wasAcked( message_t* p_msg ) {
-    return (call CC2420Packet.getMetadata( p_msg ))->ack;
-  }
-
-  async command void CC2420Packet.setPower( message_t* p_msg, uint8_t power ) {
-    if ( power > 31 )
-      power = 31;
-    (call CC2420Packet.getMetadata( p_msg ))->tx_power = power;
-  }
-
-  async command uint8_t CC2420Packet.getPower( message_t* p_msg ) {
-    return (call CC2420Packet.getMetadata( p_msg ))->tx_power;
-  }
-   
-  async command int8_t CC2420Packet.getRssi( message_t* p_msg ) {
-    return (call CC2420Packet.getMetadata( p_msg ))->rssi;
-  }
-
-  async command error_t CC2420Packet.getLqi( message_t* p_msg ) {
-    return (call CC2420Packet.getMetadata( p_msg ))->lqi;
-  }
-
-}
diff --git a/tos/chips/cc2420/CC2420Power.nc b/tos/chips/cc2420/CC2420Power.nc
deleted file mode 100644 (file)
index 74012e5..0000000
+++ /dev/null
@@ -1,99 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Arch Rock Corporation
- * All rights reserved.
- *
- * 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 the Arch Rock Corporation 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
- * ARCHED ROCK OR ITS 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
- */
-
-/**
- * An HAL abstraction of the ChipCon CC2420 radio. This abstraction
- * deals specifically with radio power operations (e.g. voltage
- * regulator, oscillator, etc). However, it does not include
- * transmission power, see the CC2420Config interface.
- *
- * @author Jonathan Hui <jhui@archrock.com>
- * @version $Revision$ $Date$
- */
-
-interface CC2420Power {
-
-  /**
-   * Start the voltage regulator on the CC2420. On SUCCESS,
-   * <code>startVReg()</code> will be signalled when the voltage
-   * regulator is fully on.
-   *
-   * @return SUCCESS if the request was accepted, FAIL otherwise.
-   */
-  async command error_t startVReg();
-
-  /**
-   * Signals that the voltage regulator has been started.
-   */
-  async event void startVRegDone();
-  
-  /**
-   * Stop the voltage regulator immediately.
-   *
-   * @return SUCCESS always
-   */
-  async command error_t stopVReg();
-
-  /**
-   * Start the oscillator. On SUCCESS, <code>startOscillator</code>
-   * will be signalled when the oscillator has been started.
-   *
-   * @return SUCCESS if the request was accepted, FAIL otherwise.
-   */
-  async command error_t startOscillator();
-
-  /**
-   * Signals that the oscillator has been started.
-   */
-  async event void startOscillatorDone();
-
-  /**
-   * Stop the oscillator.
-   *
-   * @return SUCCESS if the oscillator was stopped, FAIL otherwise.
-   */
-  async command error_t stopOscillator();
-
-  /**
-   * Enable RX.
-   *
-   * @return SUCCESS if receive mode has been enabled, FAIL otherwise.
-   */
-  async command error_t rxOn();
-
-  /**
-   * Disable RX.
-   *
-   * @return SUCCESS if receive mode has been disabled, FAIL otherwise.
-   */
-  async command error_t rfOff();
-
-}
diff --git a/tos/chips/cc2420/CC2420Ram.nc b/tos/chips/cc2420/CC2420Ram.nc
deleted file mode 100644 (file)
index a41712d..0000000
+++ /dev/null
@@ -1,65 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Arch Rock Corporation
- * All rights reserved.
- *
- * 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 the Arch Rock Corporation 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
- * ARCHED ROCK OR ITS 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
- */
-
-/**
- * HAL abstraction for accessing theRAM of a ChipCon CC2420 radio.
- *
- * @author Jonathan Hui <jhui@archrock.com>
- * @version $Revision$ $Date$
- */
-
-#include "CC2420.h"
-
-interface CC2420Ram {
-
-  /**
-   * Read data from a RAM. This operation is sychronous.
-   *
-   * @param offset within the field.
-   * @param data a pointer to the receive buffer.
-   * @param length number of bytes to read.
-   * @return status byte returned when sending the last byte
-   * of the SPI transaction.
-   */
-  async command cc2420_status_t read( uint8_t offset, uint8_t* data, uint8_t length );
-
-  /**
-   * Write data to RAM. This operation is sychronous.
-   *
-   * @param offset within the field.
-   * @param data a pointer to the send buffer.
-   * @param length number of bytes to write.
-   * @return status byte returned when sending the last address byte
-   * of the SPI transaction.
-   */
-  async command cc2420_status_t write( uint8_t offset, uint8_t* data, uint8_t length );
-
-}
diff --git a/tos/chips/cc2420/CC2420Receive.nc b/tos/chips/cc2420/CC2420Receive.nc
deleted file mode 100644 (file)
index 70230b0..0000000
+++ /dev/null
@@ -1,64 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Arch Rock Corporation
- * All rights reserved.
- *
- * 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 the Arch Rock Corporation 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
- * ARCHED ROCK OR ITS 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
- */
-
-/**
- * Low-level abstraction of the receive path implementation for the
- * ChipCon CC2420 radio.
- *
- * @author Jonathan Hui <jhui@archrock.com>
- * @version $Revision$ $Date$
- */
-
-interface CC2420Receive {
-
-  /**
-   * Notification that an SFD capture has occured.
-   *
-   * @param time at which the capture happened.
-   */
-  async command void sfd( uint16_t time );
-
-  /**
-   * Notification that the packet has been dropped by the radio
-   * (e.g. due to address rejection).
-   */
-  async command void sfd_dropped();
-
-  /**
-   * Signals that a message has been received.
-   *
-   * @param type of the message received.
-   * @param message pointer to message received.
-   */
-  async event void receive( uint8_t type, message_t* message );
-
-}
-
diff --git a/tos/chips/cc2420/CC2420ReceiveC.nc b/tos/chips/cc2420/CC2420ReceiveC.nc
deleted file mode 100644 (file)
index 452aad2..0000000
+++ /dev/null
@@ -1,77 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Arch Rock Corporation
- * All rights reserved.
- *
- * 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 the Arch Rock Corporation 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
- * ARCHED ROCK OR ITS 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
- */
-
-/**
- * Implementation of the receive path for the ChipCon CC2420 radio.
- *
- * @author Jonathan Hui <jhui@archrock.com>
- * @version $Revision$ $Date$
- */
-
-configuration CC2420ReceiveC {
-
-  provides interface StdControl;
-  provides interface CC2420Receive;
-  provides interface Receive;
-
-}
-
-implementation {
-  components MainC;
-  components CC2420ReceiveP;
-  components CC2420PacketC;
-  components ActiveMessageAddressC;
-  components new CC2420SpiC() as Spi;
-
-  components HplCC2420PinsC as Pins;
-  components HplCC2420InterruptsC as InterruptsC;
-
-  components LedsC as Leds;
-  CC2420ReceiveP.Leds -> Leds;
-
-  StdControl = CC2420ReceiveP;
-  CC2420Receive = CC2420ReceiveP;
-  Receive = CC2420ReceiveP;
-
-  MainC.SoftwareInit -> CC2420ReceiveP;
-  
-  CC2420ReceiveP.CSN -> Pins.CSN;
-  CC2420ReceiveP.FIFO -> Pins.FIFO;
-  CC2420ReceiveP.FIFOP -> Pins.FIFOP;
-  CC2420ReceiveP.InterruptFIFOP -> InterruptsC.InterruptFIFOP;
-  CC2420ReceiveP.SpiResource -> Spi;
-  CC2420ReceiveP.RXFIFO -> Spi.RXFIFO;
-  CC2420ReceiveP.SFLUSHRX -> Spi.SFLUSHRX;
-  CC2420ReceiveP.SACK -> Spi.SACK;
-  CC2420ReceiveP.CC2420Packet -> CC2420PacketC;
-  CC2420ReceiveP.amAddress -> ActiveMessageAddressC;
-
-}
diff --git a/tos/chips/cc2420/CC2420ReceiveP.nc b/tos/chips/cc2420/CC2420ReceiveP.nc
deleted file mode 100644 (file)
index b024079..0000000
+++ /dev/null
@@ -1,381 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Arch Rock Corporation
- * All rights reserved.
- *
- * 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 the Arch Rock Corporation 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
- * ARCHED ROCK OR ITS 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
- */
-
-/**
- * @author Jonathan Hui <jhui@archrock.com>
- * @author David Moss
- * @author Jung Il Choi
- * @version $Revision$ $Date$
- */
-
-module CC2420ReceiveP {
-
-  provides interface Init;
-  provides interface StdControl;
-  provides interface CC2420Receive;
-  provides interface Receive;
-
-  uses interface GeneralIO as CSN;
-  uses interface GeneralIO as FIFO;
-  uses interface GeneralIO as FIFOP;
-  uses interface GpioInterrupt as InterruptFIFOP;
-
-  uses interface Resource as SpiResource;
-  uses interface CC2420Fifo as RXFIFO;
-  uses interface CC2420Strobe as SACK;
-  uses interface CC2420Strobe as SFLUSHRX;
-  uses interface CC2420Packet;
-  
-  uses interface Leds;
-  uses async command am_addr_t amAddress();
-}
-
-implementation {
-
-  typedef enum {
-    S_STOPPED,
-    S_STARTED,
-    S_RX_HEADER,
-    S_RX_PAYLOAD,
-  } cc2420_receive_state_t;
-
-  enum {
-    RXFIFO_SIZE = 128,
-    TIMESTAMP_QUEUE_SIZE = 8,
-  };
-
-  uint16_t m_timestamp_queue[ TIMESTAMP_QUEUE_SIZE ];
-  
-  uint8_t m_timestamp_head;
-  
-  uint8_t m_timestamp_size;
-  
-  uint8_t m_missed_packets;
-
-  bool fallingEdgeEnabled;
-  
-  norace uint8_t m_bytes_left;
-  
-  norace message_t* m_p_rx_buf;
-
-  message_t m_rx_buf;
-  
-  cc2420_receive_state_t m_state;
-  
-  /***************** Prototypes ****************/
-  void reset_state();
-  void beginReceive();
-  void receive();
-  void waitForNextPacket();
-  void flush();
-  
-  task void receiveDone_task();
-  
-  /***************** Init Commands ****************/
-  command error_t Init.init() {
-    fallingEdgeEnabled = FALSE;
-    m_p_rx_buf = &m_rx_buf;
-    return SUCCESS;
-  }
-
-  /***************** StdControl ****************/
-  command error_t StdControl.start() {
-    atomic {
-      reset_state();
-      m_state = S_STARTED;
-        
-      // Warning: MicaZ problems have been encountered with the following line
-      // after it follows a .disable command
-      call InterruptFIFOP.enableFallingEdge();
-    }
-    return SUCCESS;
-  }
-
-
-  
-  command error_t StdControl.stop() {
-    atomic {
-      m_state = S_STOPPED;
-      reset_state();
-      
-      call SpiResource.release();
-      
-      // Warning: MicaZ problems have been encountered with the following line
-      // followed by a re-enable.  The re-enable doesn't occur.
-      call InterruptFIFOP.disable();
-    }
-    return SUCCESS;
-  }
-
-  /***************** Receive Commands ****************/
-  command void* Receive.getPayload(message_t* m, uint8_t* len) {
-    if (len != NULL) {
-      *len = ((uint8_t*) (call CC2420Packet.getHeader( m_p_rx_buf )))[0];
-    }
-    return m->data;
-  }
-
-  command uint8_t Receive.payloadLength(message_t* m) {
-    uint8_t* buf = (uint8_t*)(call CC2420Packet.getHeader( m_p_rx_buf ));
-    return buf[0];
-  }
-  
-  
-  /***************** CC2420Receive Commands ****************/
-  /**
-   * Start frame delimiter signifies the beginning/end of a packet
-   * See the CC2420 datasheet for details.
-   */
-  async command void CC2420Receive.sfd( uint16_t time ) {
-    if ( m_timestamp_size < TIMESTAMP_QUEUE_SIZE ) {
-      uint8_t tail =  ( ( m_timestamp_head + m_timestamp_size ) % 
-                        TIMESTAMP_QUEUE_SIZE );
-      m_timestamp_queue[ tail ] = time;
-      m_timestamp_size++;
-    }
-  }
-
-  async command void CC2420Receive.sfd_dropped() {
-    if ( m_timestamp_size ) {
-      m_timestamp_size--;
-    }
-  }
-
-
-  /***************** InterruptFIFOP Events ****************/
-  async event void InterruptFIFOP.fired() {
-    if ( m_state == S_STARTED ) {
-      beginReceive();
-      
-    } else {
-      m_missed_packets++;
-    }
-  }
-  
-  
-  /***************** SpiResource Events ****************/
-  event void SpiResource.granted() {
-    receive();
-  }
-  
-  /***************** RXFIFO Events ****************/
-  /**
-   * We received some bytes from the SPI bus.  Process them in the context
-   * of the state we're in
-   */
-  async event void RXFIFO.readDone( uint8_t* rx_buf, uint8_t rx_len,
-                                    error_t error ) {
-    cc2420_header_t* header = call CC2420Packet.getHeader( m_p_rx_buf );
-    cc2420_metadata_t* metadata = call CC2420Packet.getMetadata( m_p_rx_buf );
-    uint8_t* buf = (uint8_t*) header;
-    uint8_t length = buf[ 0 ];
-
-    switch( m_state ) {
-
-    case S_RX_HEADER:
-      m_state = S_RX_PAYLOAD;
-      if ( length + 1 > m_bytes_left ) {
-        flush();
-        
-      } else {
-        if ( !call FIFO.get() && !call FIFOP.get() ) {
-          m_bytes_left -= length + 1;
-        }
-        
-        if(length <= MAC_PACKET_SIZE) {
-          if(length > 0) {
-            // Length is in bounds; read in this packet
-            call RXFIFO.continueRead((uint8_t*)(call CC2420Packet.getHeader(
-                m_p_rx_buf )) + 1, length);
-                
-          } else {
-            // Length == 0; start reading the next packet
-            call CSN.set();
-            call SpiResource.release();
-            waitForNextPacket();
-          }
-          
-        } else {
-          // Length is too large; we have to flush the entire Rx FIFO
-          flush();
-        }
-      }
-      break;
-      
-    case S_RX_PAYLOAD:
-      call CSN.set();
-      
-#if !defined(CC2420_NO_ACKNOWLEDGEMENTS) && !defined(CC2420_HW_ACKNOWLEDGEMENTS)
-      // Sorry about the preprocessing stuff. BaseStation and hw acks depends on it.
-      if (((( header->fcf >> IEEE154_FCF_ACK_REQ ) & 0x01) == 1) 
-          && (header->dest == call amAddress())
-          && ((( header->fcf >> IEEE154_FCF_FRAME_TYPE ) & 7) == IEEE154_TYPE_DATA)) {
-        call CSN.clr();
-        call SACK.strobe();
-        call CSN.set();
-      }
-#endif
-      
-      call SpiResource.release();
-      
-      if ( m_timestamp_size ) {
-        if ( length > 10 ) {
-          metadata->time = m_timestamp_queue[ m_timestamp_head ];
-          m_timestamp_head = ( m_timestamp_head + 1 ) % TIMESTAMP_QUEUE_SIZE;
-          m_timestamp_size--;
-        }
-      } else {
-        metadata->time = 0xffff;
-      }
-      
-      // We may have received an ack that should be processed by Transmit
-      if ( ( buf[ length ] >> 7 ) && rx_buf ) {
-        uint8_t type = ( header->fcf >> IEEE154_FCF_FRAME_TYPE ) & 7;
-        signal CC2420Receive.receive( type, m_p_rx_buf );
-        if ( type == IEEE154_TYPE_DATA ) {
-          post receiveDone_task();
-          return;
-        }
-      }
-      
-      waitForNextPacket();
-      break;
-
-    default:
-      call CSN.set();
-      call SpiResource.release();
-      break;
-      
-    }
-    
-  }
-
-  async event void RXFIFO.writeDone( uint8_t* tx_buf, uint8_t tx_len, error_t error ) {
-  }  
-  
-  /***************** Tasks *****************/
-  /**
-   * Fill in metadata details, pass the packet up the stack, and
-   * get the next packet.
-   */
-  task void receiveDone_task() {
-    cc2420_header_t* header = call CC2420Packet.getHeader( m_p_rx_buf );
-    cc2420_metadata_t* metadata = call CC2420Packet.getMetadata( m_p_rx_buf );
-    uint8_t* buf = (uint8_t*)header;
-    uint8_t length = buf[ 0 ];
-    
-    metadata->crc = buf[ length ] >> 7;
-    metadata->rssi = buf[ length - 1 ];
-    metadata->lqi = buf[ length ] & 0x7f;
-    m_p_rx_buf = signal Receive.receive( m_p_rx_buf, m_p_rx_buf->data, 
-                                         length );
-
-    waitForNextPacket();
-  }
-
-  
-  /****************** Functions ****************/
-  /**
-   * Attempt to acquire the SPI bus to receive a packet.
-   */
-  void beginReceive() { 
-    m_state = S_RX_HEADER;
-    
-    if ( call SpiResource.immediateRequest() == SUCCESS ) {
-      receive();
-    } else {
-      call SpiResource.request();
-    }
-  }
-  
-  /**
-   * Flush out the Rx FIFO
-   */
-  void flush() {
-    reset_state();
-    call CSN.set();
-    call CSN.clr();
-    call SFLUSHRX.strobe();
-    call SFLUSHRX.strobe();
-    call CSN.set();
-    call SpiResource.release();
-    waitForNextPacket();
-  }
-  
-  /**
-   * The first byte of each packet is the length byte.  Read in that single
-   * byte, and then read in the rest of the packet.  The CC2420 could contain
-   * multiple packets that have been buffered up, so if something goes wrong, 
-   * we necessarily want to flush out the FIFO unless we have to.
-   */
-  void receive() {
-    call CSN.clr();
-    call RXFIFO.beginRead( (uint8_t*)(call CC2420Packet.getHeader( m_p_rx_buf )), 1 );
-  }
-
-
-  /**
-   * Determine if there's a packet ready to go, or if we should do nothing
-   * until the next packet arrives
-   */
-  void waitForNextPacket() {
-    atomic {
-      if ( m_state == S_STOPPED ) {
-        return;
-      }
-
-      if ( ( m_missed_packets && call FIFO.get() ) || !call FIFOP.get() ) {
-        // A new packet is buffered up and ready to go
-        if ( m_missed_packets ) {
-          m_missed_packets--;
-        }
-        
-        beginReceive();
-        
-      } else {
-        // Wait for the next packet to arrive
-        m_state = S_STARTED;
-        m_missed_packets = 0;
-      }
-    }
-  }
-  
-  /**
-   * Reset this component
-   */
-  void reset_state() {
-    m_bytes_left = RXFIFO_SIZE;
-    m_timestamp_head = 0;
-    m_timestamp_size = 0;
-    m_missed_packets = 0;
-  }
-
-}
diff --git a/tos/chips/cc2420/CC2420Register.nc b/tos/chips/cc2420/CC2420Register.nc
deleted file mode 100644 (file)
index a5cc3c6..0000000
+++ /dev/null
@@ -1,57 +0,0 @@
-/*                                                                     tab:4
- * "Copyright (c) 2005 Stanford University. All rights reserved.
- *
- * Permission to use, copy, modify, and distribute this software and
- * its documentation for any purpose, without fee, and without written
- * agreement is hereby granted, provided that the above copyright
- * notice, the following two paragraphs and the author appear in all
- * copies of this software.
- * 
- * IN NO EVENT SHALL STANFORD UNIVERSITY BE LIABLE TO ANY PARTY FOR
- * DIRECT, INDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES
- * ARISING OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN
- * IF STANFORD UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH
- * DAMAGE.
- * 
- * STANFORD UNIVERSITY SPECIFICALLY DISCLAIMS ANY WARRANTIES,
- * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
- * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.  THE SOFTWARE
- * PROVIDED HEREUNDER IS ON AN "AS IS" BASIS, AND STANFORD UNIVERSITY
- * HAS NO OBLIGATION TO PROVIDE MAINTENANCE, SUPPORT, UPDATES,
- * ENHANCEMENTS, OR MODIFICATIONS."
- *
- */
-
-/**
- * Interface representing one of the Read/Write registers on the
- * CC2420 radio. The return values (when appropriate) refer to the
- * status byte returned on the CC2420 SO pin. A full list of RW
- * registers can be found on page 61 of the CC2420 datasheet (rev
- * 1.2). Page 25 of the same document describes the protocol for
- * interacting with these registers over the CC2420 SPI bus.
- *
- * @author Philip Levis
- * @version $Revision$ $Date$
- */
-
-#include "CC2420.h"
-
-interface CC2420Register {
-
-  /**
-   * Read a 16-bit data word from the register.
-   *
-   * @param data pointer to place the register value.
-   * @return status byte from the read.
-   */
-  async command cc2420_status_t read(uint16_t* data);
-
-  /**
-   * Write a 16-bit data word to the register.
-   * 
-   * @param data value to write to register.
-   * @return status byte from the write.
-   */
-  async command cc2420_status_t write(uint16_t data);
-
-}
diff --git a/tos/chips/cc2420/CC2420SpiC.nc b/tos/chips/cc2420/CC2420SpiC.nc
deleted file mode 100644 (file)
index 6e4cb21..0000000
+++ /dev/null
@@ -1,125 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Arch Rock Corporation
- * All rights reserved.
- *
- * 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 the Arch Rock Corporation 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
- * ARCHED ROCK OR ITS 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
- */
-
-/**
- * Implementation of basic SPI primitives for the ChipCon CC2420 radio.
- *
- * @author Jonathan Hui <jhui@archrock.com>
- * @version $Revision$ $Date$
- */
-
-generic configuration CC2420SpiC() {
-
-  provides interface SplitControl;
-  provides interface Resource;
-
-  // commands
-  provides interface CC2420Strobe as SFLUSHRX;
-  provides interface CC2420Strobe as SFLUSHTX;
-  provides interface CC2420Strobe as SNOP;
-  provides interface CC2420Strobe as SRXON;
-  provides interface CC2420Strobe as SRFOFF;
-  provides interface CC2420Strobe as STXON;
-  provides interface CC2420Strobe as STXONCCA;
-  provides interface CC2420Strobe as SXOSCON;
-  provides interface CC2420Strobe as SXOSCOFF;
-  
-  provides interface CC2420Strobe as SACK;
-
-  // registers
-  provides interface CC2420Register as FSCTRL;
-  provides interface CC2420Register as IOCFG0;
-  provides interface CC2420Register as IOCFG1;
-  provides interface CC2420Register as MDMCTRL0;
-  provides interface CC2420Register as MDMCTRL1;
-  provides interface CC2420Register as TXCTRL;
-  provides interface CC2420Register as RXCTRL1;
-  provides interface CC2420Register as RSSI;
-
-  // ram
-  provides interface CC2420Ram as IEEEADR;
-  provides interface CC2420Ram as PANID;
-  provides interface CC2420Ram as SHORTADR;
-  provides interface CC2420Ram as TXFIFO_RAM;
-
-  // fifos
-  provides interface CC2420Fifo as RXFIFO;
-  provides interface CC2420Fifo as TXFIFO;
-
-}
-
-implementation {
-
-  enum {
-    CLIENT_ID = unique( "CC2420Spi.Resource" ),
-  };
-
-  components HplCC2420PinsC as Pins;
-  components CC2420SpiP as Spi;
-  
-  Resource = Spi.Resource[ CLIENT_ID ];
-  SplitControl = Spi.SplitControl;
-  
-  // commands
-  SFLUSHRX = Spi.Strobe[ CC2420_SFLUSHRX ];
-  SFLUSHTX = Spi.Strobe[ CC2420_SFLUSHTX ];
-  SNOP = Spi.Strobe[ CC2420_SNOP ];
-  SRXON = Spi.Strobe[ CC2420_SRXON ];
-  SRFOFF = Spi.Strobe[ CC2420_SRFOFF ];
-  STXON = Spi.Strobe[ CC2420_STXON ];
-  STXONCCA = Spi.Strobe[ CC2420_STXONCCA ];
-  SXOSCON = Spi.Strobe[ CC2420_SXOSCON ];
-  SXOSCOFF = Spi.Strobe[ CC2420_SXOSCOFF ];
-  
-  SACK = Spi.Strobe[ CC2420_SACK ];
-
-  // registers
-  FSCTRL = Spi.Reg[ CC2420_FSCTRL ];
-  IOCFG0 = Spi.Reg[ CC2420_IOCFG0 ];
-  IOCFG1 = Spi.Reg[ CC2420_IOCFG1 ];
-  MDMCTRL0 = Spi.Reg[ CC2420_MDMCTRL0 ];
-  MDMCTRL1 = Spi.Reg[ CC2420_MDMCTRL1 ];
-  TXCTRL = Spi.Reg[ CC2420_TXCTRL ];
-  RXCTRL1 = Spi.Reg[ CC2420_RXCTRL1 ];
-  RSSI = Spi.Reg[ CC2420_RSSI ];
-
-  // ram
-  IEEEADR = Spi.Ram[ CC2420_RAM_IEEEADR ];
-  PANID = Spi.Ram[ CC2420_RAM_PANID ];
-  SHORTADR = Spi.Ram[ CC2420_RAM_SHORTADR ];
-  TXFIFO_RAM = Spi.Ram[ CC2420_RAM_TXFIFO ];
-
-  // fifos
-  RXFIFO = Spi.Fifo[ CC2420_RXFIFO ];
-  TXFIFO = Spi.Fifo[ CC2420_TXFIFO ];
-
-}
-
diff --git a/tos/chips/cc2420/CC2420SpiImplP.nc b/tos/chips/cc2420/CC2420SpiImplP.nc
deleted file mode 100644 (file)
index f70fba3..0000000
+++ /dev/null
@@ -1,355 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Arch Rock Corporation
- * All rights reserved.
- *
- * 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 the Arch Rock Corporation 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
- * ARCHED ROCK OR ITS 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
- */
-
-/**
- * @author Jonathan Hui <jhui@archrock.com>
- * @author David Moss
- * @author Roman Lim
- * @version $Revision$ $Date$
- */
-
-module CC2420SpiImplP {
-
-  provides interface SplitControl;
-  provides interface Resource[ uint8_t id ];
-  provides interface CC2420Fifo as Fifo[ uint8_t id ];
-  provides interface CC2420Ram as Ram[ uint16_t id ];
-  provides interface CC2420Register as Reg[ uint8_t id ];
-  provides interface CC2420Strobe as Strobe[ uint8_t id ];
-
-  uses interface Resource as SpiResource;
-  uses interface SpiByte;
-  uses interface SpiPacket;
-  uses interface Leds;
-
-}
-
-implementation {
-
-  enum {
-    RESOURCE_COUNT = uniqueCount( "CC2420Spi.Resource" ),
-    NO_HOLDER = 0xff,
-  };
-
-  enum {
-    S_IDLE,
-    S_GRANTING,
-    S_BUSY,
-  };
-
-  norace uint16_t m_addr;
-  
-  uint8_t m_requests = 0;
-  
-  uint8_t m_holder = NO_HOLDER;
-  
-  uint8_t m_state = S_IDLE;
-
-  bool enabled = FALSE;
-  
-  /***************** Prototypes ****************/
-  task void waitForIdle();
-  
-  /***************** SplitControl Commands ****************/
-  command error_t SplitControl.start() {
-    atomic enabled = TRUE;
-    signal SplitControl.startDone(SUCCESS);
-    return SUCCESS;
-  }
-  
-  command error_t SplitControl.stop() {
-    atomic {
-      enabled = FALSE;
-      m_requests = 0;
-    }
-    ////call Leds.led1On();
-    post waitForIdle();
-    return SUCCESS;
-  }
-  
-  /***************** Resource Commands *****************/
-  async command error_t Resource.request[ uint8_t id ]() {
-    
-    if(!enabled) {
-      return EOFF;
-    }
-    
-    atomic {
-      if ( m_state != S_IDLE ) {
-        m_requests |= 1 << id;
-      } else {
-        m_holder = id;
-        m_state = S_GRANTING;
-        call SpiResource.request();
-      }
-    }
-    return SUCCESS;
-  }
-  
-  async command error_t Resource.immediateRequest[ uint8_t id ]() {
-    error_t error;
-    
-    if(!enabled) {
-      return EOFF;
-    }
-    
-    atomic {
-      if ( m_state != S_IDLE ) {
-        return EBUSY;
-      }
-      
-      error = call SpiResource.immediateRequest();
-      if ( error == SUCCESS ) {
-        m_holder = id;
-        m_state = S_BUSY;
-      }
-    }
-    return error;
-  }
-
-  async command error_t Resource.release[ uint8_t id ]() {
-    uint8_t i;
-    atomic {
-      if ( (m_holder != id) || (m_state != S_BUSY)) {
-        return FAIL;
-      }
-
-      m_holder = NO_HOLDER;
-      call SpiResource.release();
-      if ( !m_requests ) {
-        m_state = S_IDLE;
-      } else {
-        for ( i = m_holder + 1; ; i++ ) {
-          if ( i >= RESOURCE_COUNT ) {
-            i = 0;
-          }
-          
-          if ( m_requests & ( 1 << i ) ) {
-            m_holder = i;
-            m_requests &= ~( 1 << i );
-            call SpiResource.request();
-            m_state = S_GRANTING;
-            return SUCCESS;
-          }
-        }
-      }
-      return SUCCESS;
-    }
-  }
-  
-  async command uint8_t Resource.isOwner[ uint8_t id ]() {
-    atomic return (m_holder == id) & (m_state == S_BUSY);
-  }
-
-
-  /***************** Fifo Commands ****************/
-  async command cc2420_status_t Fifo.beginRead[ uint8_t addr ]( uint8_t* data, 
-                                                                uint8_t len ) {
-    
-    cc2420_status_t status = 0;
-
-    atomic {
-      if(m_state != S_BUSY) {
-        return status;
-      }
-    }
-    
-    m_addr = addr | 0x40;
-        
-    status = call SpiByte.write( m_addr );
-    call Fifo.continueRead[ addr ]( data, len );
-    
-    return status;
-    
-  }
-
-  async command error_t Fifo.continueRead[ uint8_t addr ]( uint8_t* data,
-                                                           uint8_t len ) {
-    call SpiPacket.send( NULL, data, len );
-    return SUCCESS;
-  }
-
-  async command cc2420_status_t Fifo.write[ uint8_t addr ]( uint8_t* data, 
-                                                            uint8_t len ) {
-
-    uint8_t status = 0;
-    atomic {
-      if(m_state != S_BUSY) {
-        return status;
-      }
-    }
-    
-    m_addr = addr;
-
-    status = call SpiByte.write( m_addr );
-    call SpiPacket.send( data, NULL, len );
-
-    return status;
-
-  }
-
-  /***************** RAM Commands ****************/
-  async command cc2420_status_t Ram.read[ uint16_t addr ]( uint8_t offset,
-                                                           uint8_t* data, 
-                                                           uint8_t len ) {
-
-    cc2420_status_t status = 0;
-
-    atomic {
-      if(m_state != S_BUSY) {
-        return status;
-      }
-    }
-    
-    addr += offset;
-
-    call SpiByte.write( addr | 0x80 );
-    status = call SpiByte.write( ( ( addr >> 1 ) & 0xc0 ) | 0x20 );
-    for ( ; len; len-- )
-      *data++ = call SpiByte.write( 0 );
-
-    return status;
-
-  }
-
-
-  async command cc2420_status_t Ram.write[ uint16_t addr ]( uint8_t offset,
-                                                            uint8_t* data, 
-                                                            uint8_t len ) {
-
-    cc2420_status_t status = 0;
-
-    atomic {
-      if(m_state != S_BUSY) {
-        return status;
-      }
-    }
-    
-    addr += offset;
-
-    call SpiByte.write( addr | 0x80 );
-    call SpiByte.write( ( addr >> 1 ) & 0xc0 );
-    for ( ; len; len-- )
-      status = call SpiByte.write( *data++ );
-
-    return status;
-
-  }
-
-  /***************** Register Commands ****************/
-  async command cc2420_status_t Reg.read[ uint8_t addr ]( uint16_t* data ) {
-
-    cc2420_status_t status = 0;
-    
-    atomic {
-      if(m_state != S_BUSY) {
-        return status;
-      }
-    }
-    
-    status = call SpiByte.write( addr | 0x40 );
-    *data = (uint16_t)call SpiByte.write( 0 ) << 8;
-    *data |= call SpiByte.write( 0 );
-    
-    return status;
-
-  }
-
-  async command cc2420_status_t Reg.write[ uint8_t addr ]( uint16_t data ) {
-    atomic {
-      if(m_state != S_BUSY) {
-        return 0;
-      }
-    }
-    call SpiByte.write( addr );
-    call SpiByte.write( data >> 8 );
-    return call SpiByte.write( data & 0xff );
-  }
-
-  
-  /***************** Strobe Commands ****************/
-  async command cc2420_status_t Strobe.strobe[ uint8_t addr ]() {
-    atomic {
-      if(m_state != S_BUSY) {
-        return 0;
-      }
-    }
-    
-    return call SpiByte.write( addr );
-  }
-
-  /***************** SpiResource Events ****************/
-  event void SpiResource.granted() {
-    uint8_t holder;
-    atomic { 
-        holder = m_holder;
-        m_state = S_BUSY;
-    }
-    signal Resource.granted[ holder ]();
-  }
-  
-  /***************** SpiPacket Events ****************/
-  async event void SpiPacket.sendDone( uint8_t* tx_buf, uint8_t* rx_buf, 
-                                       uint16_t len, error_t error ) {
-    if ( m_addr & 0x40 ) {
-      signal Fifo.readDone[ m_addr & ~0x40 ]( rx_buf, len, error );
-    } else {
-      signal Fifo.writeDone[ m_addr ]( tx_buf, len, error );
-    }
-  }
-  
-  
-  /***************** Tasks ****************/
-  task void waitForIdle() {
-    uint8_t currentState;
-    atomic currentState = m_state;
-    
-    if(currentState != S_IDLE) {
-      post waitForIdle();
-    } else {
-      ////call Leds.led1Off();
-      signal SplitControl.stopDone(SUCCESS);
-    }
-  }
-  
-
-  /***************** Defaults ****************/
-  default event void Resource.granted[ uint8_t id ]() {
-  }
-
-  default async event void Fifo.readDone[ uint8_t addr ]( uint8_t* rx_buf, uint8_t rx_len, error_t error ) {
-  }
-  
-  default async event void Fifo.writeDone[ uint8_t addr ]( uint8_t* tx_buf, uint8_t tx_len, error_t error ) {
-  }
-
-}
diff --git a/tos/chips/cc2420/CC2420SpiP.nc b/tos/chips/cc2420/CC2420SpiP.nc
deleted file mode 100644 (file)
index 843476e..0000000
+++ /dev/null
@@ -1,66 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Arch Rock Corporation
- * All rights reserved.
- *
- * 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 the Arch Rock Corporation 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
- * ARCHED ROCK OR ITS 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
- */
-
-/**
- * @author Jonathan Hui <jhui@archrock.com>
- * @version $Revision$ $Date$
- */
-
-configuration CC2420SpiP {
-  
-  provides interface SplitControl;
-  provides interface Resource[ uint8_t id ];
-  provides interface CC2420Fifo as Fifo[ uint8_t id ];
-  provides interface CC2420Ram as Ram[ uint16_t id ];
-  provides interface CC2420Register as Reg[ uint8_t id ];
-  provides interface CC2420Strobe as Strobe[ uint8_t id ];
-
-}
-
-implementation {
-
-  components CC2420SpiImplP as SpiP;
-  SplitControl = SpiP;
-  Resource = SpiP;
-  Fifo = SpiP;
-  Ram = SpiP;
-  Reg = SpiP;
-  Strobe = SpiP;
-
-  components new HplCC2420SpiC();
-  SpiP.SpiResource -> HplCC2420SpiC;
-  SpiP.SpiByte -> HplCC2420SpiC;
-  SpiP.SpiPacket -> HplCC2420SpiC;
-
-  components LedsC;
-  SpiP.Leds -> LedsC;
-
-}
diff --git a/tos/chips/cc2420/CC2420Strobe.nc b/tos/chips/cc2420/CC2420Strobe.nc
deleted file mode 100644 (file)
index 0e2a666..0000000
+++ /dev/null
@@ -1,47 +0,0 @@
-/*                                                                     tab:4
- * "Copyright (c) 2005 Stanford University. All rights reserved.
- *
- * Permission to use, copy, modify, and distribute this software and
- * its documentation for any purpose, without fee, and without written
- * agreement is hereby granted, provided that the above copyright
- * notice, the following two paragraphs and the author appear in all
- * copies of this software.
- * 
- * IN NO EVENT SHALL STANFORD UNIVERSITY BE LIABLE TO ANY PARTY FOR
- * DIRECT, INDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES
- * ARISING OUT OF THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN
- * IF STANFORD UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH
- * DAMAGE.
- * 
- * STANFORD UNIVERSITY SPECIFICALLY DISCLAIMS ANY WARRANTIES,
- * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
- * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.  THE SOFTWARE
- * PROVIDED HEREUNDER IS ON AN "AS IS" BASIS, AND STANFORD UNIVERSITY
- * HAS NO OBLIGATION TO PROVIDE MAINTENANCE, SUPPORT, UPDATES,
- * ENHANCEMENTS, OR MODIFICATIONS."
- *
- */
-
-/**
- * Interface representing one of the CC2420 command strobe registers.
- * Writing to one of these registers enacts a command on the CC2420,
- * such as power-up, transmission, or clear a FIFO.
- *
- * @author Philip Levis
- * @version $Revision$ $Date$
- */
-
-#include "CC2420.h"
-
-interface CC2420Strobe {
-
-  /**
-   * Send a command strobe to the register. The return value is the
-   * CC2420 status register. Table 5 on page 27 of the CC2420
-   * datasheet (v1.2) describes the contents of this register.
-   * 
-   * @return Status byte from the CC2420.
-   */
-  async command cc2420_status_t strobe();
-
-}
diff --git a/tos/chips/cc2420/CC2420TinyosNetworkC.nc b/tos/chips/cc2420/CC2420TinyosNetworkC.nc
deleted file mode 100644 (file)
index 6abf1ea..0000000
+++ /dev/null
@@ -1,92 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS 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
- */
-/**
- * Original TinyOS T-Frames use a packet header that is not compatible with
- * other 6LowPAN networks.  They do not include the network byte 
- * responsible for identifying the packing as being sourced from a TinyOS
- * network.
- *
- * TinyOS I-Frames are interoperability packets that do include a network
- * byte as defined by 6LowPAN specifications.  The I-Frame header type is
- * the default packet header used in TinyOS networks.
- *
- * Since either packet header is acceptable, this layer must do some 
- * preprocessing (sorry) to figure out whether or not it needs to include 
- * the functionality to process I-frames.  If I-Frames are used, then
- * the network byte is added on the way out and checked on the way in.
- * If the packet came from a network different from a TinyOS network, the
- * user may access it through the DispatchP's NonTinyosReceive[] Receive 
- * interface and process it in a different radio stack.
- *
- * If T-Frames are used instead, this layer is simply pass-through wiring to the
- * layer beneath.  
- *
- * Define "CC2420_IFRAME_TYPE" to use the interoperability frame and 
- * this layer
- * 
- * @author David Moss
- */
-#include "CC2420.h"
-
-configuration CC2420TinyosNetworkC {
-  provides {
-    interface Send;
-    interface Receive;
-  }
-  
-  uses {
-    interface Receive as SubReceive;
-    interface Send as SubSend;
-  }
-}
-
-implementation {
-
-#ifdef CC2420_IFRAME_TYPE
-  components CC2420TinyosNetworkP;
-  components CC2420PacketC;
-  
-  CC2420TinyosNetworkP.Send = Send;
-  CC2420TinyosNetworkP.Receive = Receive;
-  CC2420TinyosNetworkP.SubSend = SubSend;
-  CC2420TinyosNetworkP.SubReceive = SubReceive;
-  
-  CC2420TinyosNetworkP.CC2420Packet -> CC2420PacketC;
-
-#else
-  Send = SubSend;
-  Receive = SubReceive;
-#endif
-
-}
-
diff --git a/tos/chips/cc2420/CC2420TinyosNetworkP.nc b/tos/chips/cc2420/CC2420TinyosNetworkP.nc
deleted file mode 100644 (file)
index 18b3bc9..0000000
+++ /dev/null
@@ -1,116 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS 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
- */
-
-/**
- * Fills in the network ID byte for outgoing packets for compatibility with
- * other 6LowPAN networks.  Filters incoming packets that are not
- * TinyOS network compatible.  Provides the 6LowpanSnoop interface to
- * sniff for packets that were not originated from TinyOS.
- *
- * @author David Moss
- */
-#include "CC2420.h"
-
-module CC2420TinyosNetworkP {
-  provides {
-    interface Send;
-    interface Receive;
-    
-    interface Receive as NonTinyosReceive[uint8_t networkId];
-  }
-  
-  uses {
-    interface Send as SubSend;
-    interface Receive as SubReceive;
-    interface CC2420Packet;
-  }
-}
-
-implementation {
-
-  /***************** Send Commands ****************/
-  command error_t Send.send(message_t* msg, uint8_t len) {
-    (call CC2420Packet.getHeader(msg))->network = TINYOS_6LOWPAN_NETWORK_ID;
-    return call SubSend.send(msg, len);
-  }
-
-  command error_t Send.cancel(message_t* msg) {
-    return call SubSend.cancel(msg);
-  }
-
-  command uint8_t Send.maxPayloadLength() {
-    return call SubSend.maxPayloadLength();
-  }
-
-  command void* Send.getPayload(message_t* msg) {
-    return call SubSend.getPayload(msg);
-  }
-  
-  /***************** Receive Commands ****************/
-  command void* Receive.getPayload(message_t* msg, uint8_t* len) {
-    return call SubReceive.getPayload(msg, len);
-  }
-
-  command uint8_t Receive.payloadLength(message_t* msg) {
-    return call SubReceive.payloadLength(msg);
-  }
-  
-  /***************** NonTinyosReceive Commands ****************/
-  command void* NonTinyosReceive.getPayload[uint8_t networkId](message_t* msg, uint8_t* len) {
-    return call SubReceive.getPayload(msg, len);
-  }
-
-  command uint8_t NonTinyosReceive.payloadLength[uint8_t networkId](message_t* msg) {
-    return call SubReceive.payloadLength(msg);
-  }
-  
-  /***************** SubSend Events *****************/
-  event void SubSend.sendDone(message_t* msg, error_t error) {
-    signal Send.sendDone(msg, error);
-  }
-  
-  /***************** SubReceive Events ***************/
-  event message_t *SubReceive.receive(message_t *msg, void *payload, uint8_t len) {
-    if((call CC2420Packet.getHeader(msg))->network == TINYOS_6LOWPAN_NETWORK_ID) {
-      return signal Receive.receive(msg, payload, len);
-      
-    } else {
-      return signal NonTinyosReceive.receive[(call CC2420Packet.getHeader(msg))->network](msg, payload, len);
-    }
-  }
-  
-  /***************** Defaults ****************/
-  default event message_t *NonTinyosReceive.receive[uint8_t networkId](message_t *msg, void *payload, uint8_t len) {
-    return msg;
-  }
-  
-}
diff --git a/tos/chips/cc2420/CC2420Transmit.nc b/tos/chips/cc2420/CC2420Transmit.nc
deleted file mode 100644 (file)
index d30a84b..0000000
+++ /dev/null
@@ -1,85 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Arch Rock Corporation
- * All rights reserved.
- *
- * 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 the Arch Rock Corporation 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
- * ARCHED ROCK OR ITS 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
- */
-
-/**
- * Low-level abstraction for the transmit path implementaiton of the
- * ChipCon CC2420 radio.
- *
- * @author Jonathan Hui <jhui@archrock.com>
- * @version $Revision$ $Date$
- */
-
-interface CC2420Transmit {
-
-  /**
-   * Send a message
-   *
-   * @param p_msg message to send.
-   * @param useCca TRUE if this Tx should use clear channel assessments
-   * @return SUCCESS if the request was accepted, FAIL otherwise.
-   */
-  async command error_t send( message_t* p_msg, bool useCca );
-
-  /**
-   * Send the previous message again
-   * @param useCca TRUE if this re-Tx should use clear channel assessments
-   * @return SUCCESS if the request was accepted, FAIL otherwise.
-   */
-  async command error_t resend(bool useCca);
-
-  /**
-   * Cancel sending of the message.
-   *
-   * @return SUCCESS if the request was accepted, FAIL otherwise.
-   */
-  async command error_t cancel();
-
-  /**
-   * Signal that a message has been sent
-   *
-   * @param p_msg message to send.
-   * @param error notifaction of how the operation went.
-   */
-  async event void sendDone( message_t* p_msg, error_t error );
-
-  /**
-   * Modify the contents of a packet. This command can only be used
-   * when an SFD capture event for the sending packet is signalled.
-   *
-   * @param offset in the message to start modifying.
-   * @param buf to data to write
-   * @param len of bytes to write
-   * @return SUCCESS if the request was accepted, FAIL otherwise.
-   */
-  async command error_t modify( uint8_t offset, uint8_t* buf, uint8_t len );
-
-}
-
diff --git a/tos/chips/cc2420/CC2420TransmitC.nc b/tos/chips/cc2420/CC2420TransmitC.nc
deleted file mode 100644 (file)
index 12405d4..0000000
+++ /dev/null
@@ -1,98 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Arch Rock Corporation
- * All rights reserved.
- *
- * 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 the Arch Rock Corporation 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
- * ARCHED ROCK OR ITS 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
- */
-
-/**
- * Implementation of the transmit path for the ChipCon CC2420 radio.
- *
- * @author Jonathan Hui <jhui@archrock.com>
- * @version $Revision$ $Date$
- */
-
-#include "IEEE802154.h"
-
-configuration CC2420TransmitC {
-
-  provides {
-    interface StdControl;
-    interface CC2420Transmit;
-    interface RadioBackoff;
-    interface RadioTimeStamping;
-    interface CC2420Cca;
-  }
-}
-
-implementation {
-
-  components CC2420TransmitP;
-  StdControl = CC2420TransmitP;
-  CC2420Transmit = CC2420TransmitP;
-  RadioBackoff = CC2420TransmitP;
-  RadioTimeStamping = CC2420TransmitP;
-  CC2420Cca = CC2420TransmitP;
-
-  components MainC;
-  MainC.SoftwareInit -> CC2420TransmitP;
-  MainC.SoftwareInit -> Alarm;
-  
-  components AlarmMultiplexC as Alarm;
-  CC2420TransmitP.BackoffTimer -> Alarm;
-
-  components HplCC2420PinsC as Pins;
-  CC2420TransmitP.CCA -> Pins.CCA;
-  CC2420TransmitP.CSN -> Pins.CSN;
-  CC2420TransmitP.SFD -> Pins.SFD;
-
-  components HplCC2420InterruptsC as Interrupts;
-  CC2420TransmitP.CaptureSFD -> Interrupts.CaptureSFD;
-
-  components new CC2420SpiC() as Spi;
-  CC2420TransmitP.SpiResource -> Spi;
-  CC2420TransmitP.SNOP        -> Spi.SNOP;
-  CC2420TransmitP.STXON       -> Spi.STXON;
-  CC2420TransmitP.STXONCCA    -> Spi.STXONCCA;
-  CC2420TransmitP.SFLUSHTX    -> Spi.SFLUSHTX;
-  CC2420TransmitP.TXCTRL      -> Spi.TXCTRL;
-  CC2420TransmitP.TXFIFO      -> Spi.TXFIFO;
-  CC2420TransmitP.TXFIFO_RAM  -> Spi.TXFIFO_RAM;
-  CC2420TransmitP.MDMCTRL1    -> Spi.MDMCTRL1;
-  
-  components CC2420ReceiveC;
-  CC2420TransmitP.CC2420Receive -> CC2420ReceiveC;
-  
-  components new TimerMilliC() as LplDisableTimerC;
-  CC2420TransmitP.LplDisableTimer -> LplDisableTimerC;
-  
-  components CC2420PacketC;
-  CC2420TransmitP.CC2420Packet -> CC2420PacketC;
-  
-  components LedsC;
-  CC2420TransmitP.Leds -> LedsC;
-}
diff --git a/tos/chips/cc2420/CC2420TransmitP.nc b/tos/chips/cc2420/CC2420TransmitP.nc
deleted file mode 100644 (file)
index b1a43f6..0000000
+++ /dev/null
@@ -1,774 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Arch Rock Corporation
- * All rights reserved.
- *
- * 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 the Arch Rock Corporation 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
- * ARCHED ROCK OR ITS 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
- */
-
-/**
- * @author Jonathan Hui <jhui@archrock.com>
- * @author David Moss
- * @author Jung Il Choi
- * @version $Revision$ $Date$
- */
-
-#include "CC2420.h"
-#include "crc.h"
-
-module CC2420TransmitP {
-
-  provides interface Init;
-  provides interface StdControl;
-  provides interface CC2420Transmit as Send;
-  provides interface RadioBackoff;
-  provides interface RadioTimeStamping as TimeStamp;
-  provides interface CC2420Cca;
-  
-  uses interface Alarm<T32khz,uint32_t> as BackoffTimer;
-  uses interface CC2420Packet;
-  uses interface GpioCapture as CaptureSFD;
-  uses interface GeneralIO as CCA;
-  uses interface GeneralIO as CSN;
-  uses interface GeneralIO as SFD;
-
-  uses interface Resource as SpiResource;
-  uses interface CC2420Fifo as TXFIFO;
-  uses interface CC2420Ram as TXFIFO_RAM;
-  uses interface CC2420Register as TXCTRL;
-  uses interface CC2420Strobe as SNOP;
-  uses interface CC2420Strobe as STXON;
-  uses interface CC2420Strobe as STXONCCA;
-  uses interface CC2420Strobe as SFLUSHTX;
-  uses interface CC2420Register as MDMCTRL1;
-
-  uses interface Timer<TMilli> as LplDisableTimer;
-  uses interface CC2420Receive;
-  uses interface Leds;
-}
-
-implementation {
-
-  typedef enum {
-    S_STOPPED,
-    S_STARTED,
-    S_LOAD,
-    S_SAMPLE_CCA,
-    S_BEGIN_TRANSMIT,
-    S_SFD,
-    S_EFD,
-    S_ACK_WAIT,
-    S_LOAD_CANCEL,
-    S_TX_CANCEL,
-    S_CCA_CANCEL,
-  } cc2420_transmit_state_t;
-
-  // This specifies how many jiffies the stack should wait after a
-  // TXACTIVE to receive an SFD interrupt before assuming something is
-  // wrong and aborting the send. There seems to be a condition
-  // on the micaZ where the SFD interrupt is never handled.
-  enum {
-    CC2420_ABORT_PERIOD = 320
-  };
-  
-  norace message_t *m_msg;
-  
-  norace bool m_cca;
-  
-  norace uint8_t m_tx_power;
-  
-  cc2420_transmit_state_t m_state = S_STOPPED;
-  
-  bool m_receiving = FALSE;
-  
-  uint16_t m_prev_time;
-  
-  bool signalSendDone;
-  
-  /** TRUE if the current lpl tx is taking place with continuous modulation */
-  norace bool continuousModulation;
-  
-  /** Total CCA checks that showed no activity before the NoAck LPL send */
-  norace int8_t totalCcaChecks;
-  
-  /** The initial backoff period */
-  norace uint16_t myInitialBackoff;
-  
-  /** The congestion backoff period */
-  norace uint16_t myCongestionBackoff;
-  
-  /** The low power listening backoff period */
-  norace uint16_t myLplBackoff;
-  
-
-  /***************** Prototypes ****************/
-  error_t send( message_t *p_msg, bool cca );
-  error_t resend( bool cca );
-  void loadTXFIFO();
-  void attemptSend();
-  void congestionBackoff();
-  error_t acquireSpiResource();
-  error_t releaseSpiResource();
-  void signalDone( error_t err );
-  
-  task void startLplTimer();
-  
-  /***************** Init Commands *****************/
-  command error_t Init.init() {
-    call CCA.makeInput();
-    call CSN.makeOutput();
-    call SFD.makeInput();
-    return SUCCESS;
-  }
-
-  /***************** StdControl Commands ****************/
-  command error_t StdControl.start() {
-    atomic {
-      call CaptureSFD.captureRisingEdge();
-      m_state = S_STARTED;
-      m_receiving = FALSE;
-      m_tx_power = 0;
-    }
-    return SUCCESS;
-  }
-
-  command error_t StdControl.stop() {
-    atomic {
-      m_state = S_STOPPED;
-      call BackoffTimer.stop();
-      call CaptureSFD.disable();
-      call SpiResource.release();
-    }
-    return SUCCESS;
-  }
-
-
-  /**************** Send Commands ****************/
-  async command error_t Send.send( message_t* p_msg, bool useCca ) {
-    return send( p_msg, useCca );
-  }
-
-  async command error_t Send.resend(bool useCca) {
-    return resend( useCca );
-  }
-
-  async command error_t Send.cancel() {
-    atomic {
-      signalSendDone = FALSE;
-      switch( m_state ) {
-      case S_LOAD:
-        m_state = S_LOAD_CANCEL;
-        break;
-        
-      case S_SAMPLE_CCA:
-        m_state = S_CCA_CANCEL;
-        break;
-        
-      case S_BEGIN_TRANSMIT:
-        m_state = S_TX_CANCEL;
-        break;
-        
-      default:
-        // cancel not allowed while radio is busy transmitting
-        return FAIL;
-      }
-    }
-
-    return SUCCESS;
-  }
-
-  async command error_t Send.modify( uint8_t offset, uint8_t* buf, 
-                                     uint8_t len ) {
-    call CSN.clr();
-    call TXFIFO_RAM.write( offset, buf, len );
-    call CSN.set();
-    return SUCCESS;
-  }
-
-  /***************** RadioBackoff Commands ****************/
-  /**
-   * Must be called within a requestInitialBackoff event
-   * @param backoffTime the amount of time in some unspecified units to backoff
-   */
-  async command void RadioBackoff.setInitialBackoff(uint16_t backoffTime) {
-    myInitialBackoff = backoffTime + 1;
-  }
-  
-  /**
-   * Must be called within a requestCongestionBackoff event
-   * @param backoffTime the amount of time in some unspecified units to backoff
-   */
-  async command void RadioBackoff.setCongestionBackoff(uint16_t backoffTime) {
-    myCongestionBackoff = backoffTime + 1;
-  }
-  
-  /**
-   * Must be called within a requestLplBackoff event
-   * @param backoffTime the amount of time in some unspecified units to backoff
-   */
-  async command void RadioBackoff.setLplBackoff(uint16_t backoffTime) {
-    myLplBackoff = backoffTime + 1;
-  }
-  
-  async command void RadioBackoff.setCca(bool useCca) {
-  }
-  
-  
-  
-  /***************** CC2420Cca Commands ****************/
-  /**
-   * @return TRUE if the CCA pin shows a clear channel
-   */
-  command bool CC2420Cca.isChannelClear() {
-    return call CCA.get();
-  }
-  
-
-  /**
-   * The CaptureSFD event is actually an interrupt from the capture pin
-   * which is connected to timing circuitry and timer modules.  This
-   * type of interrupt allows us to see what time (being some relative value)
-   * the event occurred, and lets us accurately timestamp our packets.  This
-   * allows higher levels in our system to synchronize with other nodes.
-   *
-   * Because the SFD events can occur so quickly, and the interrupts go
-   * in both directions, we set up the interrupt but check the SFD pin to
-   * determine if that interrupt condition has already been met - meaning,
-   * we should fall through and continue executing code where that interrupt
-   * would have picked up and executed had our microcontroller been fast enough.
-   */
-  async event void CaptureSFD.captured( uint16_t time ) {
-    atomic {
-      switch( m_state ) {
-        
-      case S_SFD:
-        call CaptureSFD.captureFallingEdge();
-        signal TimeStamp.transmittedSFD( time, m_msg );
-        releaseSpiResource();
-        call BackoffTimer.stop();
-        m_state = S_EFD;
-        if ( ( ( (call CC2420Packet.getHeader( m_msg ))->fcf >> IEEE154_FCF_FRAME_TYPE ) & 7 ) == IEEE154_TYPE_DATA ) {
-          (call CC2420Packet.getMetadata( m_msg ))->time = time;
-        }
-        
-        if ( call SFD.get() ) {
-          break;
-        }
-        /** Fall Through because the next interrupt was already received */
-        
-      case S_EFD:
-        call CaptureSFD.captureRisingEdge();
-        if ( (call CC2420Packet.getHeader( m_msg ))->fcf & ( 1 << IEEE154_FCF_ACK_REQ ) ) {
-          m_state = S_ACK_WAIT;
-          call BackoffTimer.start( CC2420_ACK_WAIT_DELAY );
-        } else {
-        
-#ifdef NOACK_LOW_POWER_LISTENING
-          if(continuousModulation) {
-            // Wait for the LplDisableTimer to fire before running signalDone()
-            return;
-          }
-#endif
-          signalDone(SUCCESS);
-        }
-        
-        if ( !call SFD.get() ) {
-          break;
-        }
-        /** Fall Through because the next interrupt was already received */
-        
-      default:
-        if ( !m_receiving ) {
-          call CaptureSFD.captureFallingEdge();
-          signal TimeStamp.receivedSFD( time );
-          call CC2420Receive.sfd( time );
-          m_receiving = TRUE;
-          m_prev_time = time;
-          if ( call SFD.get() ) {
-            // wait for the next interrupt before moving on
-            return;
-          }
-        }
-        
-        call CaptureSFD.captureRisingEdge();
-        m_receiving = FALSE;
-        if ( time - m_prev_time < 10 ) {
-          call CC2420Receive.sfd_dropped();
-        }
-        break;
-      
-      }
-    }
-  }
-
-  /***************** CC2420Receive Events ****************/
-  /**
-   * If the packet we just received was an ack that we were expecting,
-   * our send is complete.
-   */
-  async event void CC2420Receive.receive( uint8_t type, message_t* ack_msg ) {
-    cc2420_header_t* ack_header;
-    cc2420_header_t* msg_header;
-    cc2420_metadata_t* msg_metadata;
-    uint8_t* ack_buf;
-    uint8_t length;
-
-    if ( type == IEEE154_TYPE_ACK ) {
-      ack_header = call CC2420Packet.getHeader( ack_msg );
-      msg_header = call CC2420Packet.getHeader( m_msg );
-      msg_metadata = call CC2420Packet.getMetadata( m_msg );
-      ack_buf = (uint8_t *) ack_header;
-      length = ack_header->length;
-      
-      if ( m_state == S_ACK_WAIT &&
-           msg_header->dsn == ack_header->dsn ) {
-        call BackoffTimer.stop();
-        msg_metadata->ack = TRUE;
-        msg_metadata->rssi = ack_buf[ length - 1 ];
-        msg_metadata->lqi = ack_buf[ length ] & 0x7f;
-        signalDone(SUCCESS);
-      }
-    }
-  }
-
-  /***************** SpiResource Events ****************/
-  event void SpiResource.granted() {
-    uint8_t cur_state;
-
-    atomic {
-      cur_state = m_state;
-    }
-
-    switch( cur_state ) {
-    case S_LOAD:
-      loadTXFIFO();
-      break;
-      
-    case S_BEGIN_TRANSMIT:
-      attemptSend();
-      break;
-      
-    case S_LOAD_CANCEL:
-    case S_CCA_CANCEL:
-    case S_TX_CANCEL:
-      call CSN.clr();
-      call SFLUSHTX.strobe();
-      call CSN.set();
-      releaseSpiResource();
-      atomic {
-        if (signalSendDone) {
-          signalDone(ECANCEL);
-        } else {
-          m_state = S_STARTED;
-        }
-      }
-      break;
-      
-    default:
-      releaseSpiResource();
-      break;
-    }
-  }
-  
-  /***************** TXFIFO Events ****************/
-  /**
-   * The TXFIFO is used to load packets into the transmit buffer on the
-   * chip
-   */
-  async event void TXFIFO.writeDone( uint8_t* tx_buf, uint8_t tx_len,
-                                     error_t error ) {
-
-    call CSN.set();
-    if ( m_state == S_LOAD_CANCEL ) {
-      atomic {
-        call CSN.clr();
-        call SFLUSHTX.strobe();
-        call CSN.set();
-      }
-      releaseSpiResource();
-      if (signalSendDone) {
-        signalDone(ECANCEL);
-      } else {
-        m_state = S_STARTED;
-      }
-      
-    } else if ( !m_cca ) {
-      atomic {
-        if (m_state == S_LOAD_CANCEL) {
-          m_state = S_TX_CANCEL;
-        } else {
-          m_state = S_BEGIN_TRANSMIT;
-        }
-      }
-      attemptSend();
-      
-    } else {
-      releaseSpiResource();
-      atomic {
-        if (m_state == S_LOAD_CANCEL) {
-          m_state = S_CCA_CANCEL;
-        } else {
-          m_state = S_SAMPLE_CCA;
-        }
-      }
-      
-      signal RadioBackoff.requestInitialBackoff(m_msg);
-      call BackoffTimer.start(myInitialBackoff);
-    }
-  }
-
-  
-  async event void TXFIFO.readDone( uint8_t* tx_buf, uint8_t tx_len, 
-      error_t error ) {
-  }
-  
-  
-  /***************** Timer Events ****************/
-  /**
-   * The backoff timer is mainly used to wait for a moment before trying
-   * to send a packet again. But we also use it to timeout the wait for
-   * an acknowledgement, and timeout the wait for an SFD interrupt when
-   * we should have gotten one.
-   */
-  async event void BackoffTimer.fired() {
-    atomic {
-      switch( m_state ) {
-        
-      case S_SAMPLE_CCA : 
-        // sample CCA and wait a little longer if free, just in case we
-        // sampled during the ack turn-around window
-        if ( call CCA.get() ) {
-          m_state = S_BEGIN_TRANSMIT;
-          call BackoffTimer.start( CC2420_TIME_ACK_TURNAROUND );
-          
-        } else {
-          congestionBackoff();
-        }
-        break;
-        
-      case S_CCA_CANCEL:
-        m_state = S_TX_CANCEL;
-        /** Fall Through */
-        
-      case S_BEGIN_TRANSMIT:
-      case S_TX_CANCEL:
-        if ( acquireSpiResource() == SUCCESS ) {
-          attemptSend();
-        }
-        break;
-        
-      case S_ACK_WAIT:
-        signalDone( SUCCESS );
-        break;
-
-      case S_SFD:
-        // We didn't receive an SFD interrupt within CC2420_ABORT_PERIOD
-        // jiffies. Assume something is wrong.
-        call SFLUSHTX.strobe();
-        call CaptureSFD.captureRisingEdge();
-        releaseSpiResource();
-        signalDone( ERETRY );
-        break;
-
-      default:
-        break;
-      }
-    }
-  }
-  
-  event void LplDisableTimer.fired() {
-    call MDMCTRL1.write(0 << CC2420_MDMCTRL1_TX_MODE);
-    signalDone( SUCCESS );
-  }
-    
-  /***************** Functions ****************/
-  /**
-   * Set up a message to be sent. First load it into the outbound tx buffer
-   * on the chip, then attempt to send it.
-   * @param *p_msg Pointer to the message that needs to be sent
-   * @param cca TRUE if this transmit should use clear channel assessment
-   */
-  error_t send( message_t* p_msg, bool cca ) {
-    atomic {
-      if (m_state == S_LOAD_CANCEL
-          || m_state == S_CCA_CANCEL
-          || m_state == S_TX_CANCEL) {
-        return ECANCEL;
-      }
-      
-      if ( m_state != S_STARTED ) {
-        return FAIL;
-      }
-      
-      m_state = S_LOAD;
-      m_cca = cca;
-      m_msg = p_msg;
-      totalCcaChecks = 0;
-    }
-    
-    if ( acquireSpiResource() == SUCCESS ) {
-      loadTXFIFO();
-    }
-
-    return SUCCESS;
-  }
-  
-  /**
-   * Resend a packet that already exists in the outbound tx buffer on the
-   * chip
-   * @param cca TRUE if this transmit should use clear channel assessment
-   */
-  error_t resend( bool cca ) {
-
-    atomic {
-      if (m_state == S_LOAD_CANCEL
-          || m_state == S_CCA_CANCEL
-          || m_state == S_TX_CANCEL) {
-        return ECANCEL;
-      }
-      
-      if ( m_state != S_STARTED ) {
-        return FAIL;
-      }
-      
-      m_cca = cca;
-      m_state = cca ? S_SAMPLE_CCA : S_BEGIN_TRANSMIT;
-      totalCcaChecks = 0;
-    }
-    
-    if(m_cca) {
-      if((call CC2420Packet.getMetadata( m_msg ))->rxInterval > 0) {
-        signal RadioBackoff.requestLplBackoff(m_msg);
-        call BackoffTimer.start( myLplBackoff );
-        
-      } else {
-        signal RadioBackoff.requestInitialBackoff(m_msg);
-        call BackoffTimer.start( myInitialBackoff );
-      }
-      
-    } else if ( acquireSpiResource() == SUCCESS ) {
-      attemptSend();
-    }
-    
-    return SUCCESS;
-  }
-  
-  /**
-   * Attempt to send the packet we have loaded into the tx buffer on 
-   * the radio chip.  The STXONCCA will send the packet immediately if
-   * the channel is clear.  If we're not concerned about whether or not
-   * the channel is clear (i.e. m_cca == FALSE), then STXON will send the
-   * packet without checking for a clear channel.
-   *
-   * If the packet didn't get sent, then congestion == TRUE.  In that case,
-   * we reset the backoff timer and try again in a moment.
-   *
-   * If the packet got sent, we should expect an SFD interrupt to take
-   * over, signifying the packet is getting sent.
-   */
-  void attemptSend() {
-    uint8_t status;
-    bool congestion = TRUE;
-    
-    continuousModulation = FALSE;
-    
-#ifdef NOACK_LOW_POWER_LISTENING
-      // When the message is being sent with LPL, CCA implies this is the first
-      // message.  Send it using the continuous modulation delivery
-      continuousModulation = m_cca 
-          && (call CC2420Packet.getMetadata( m_msg ))->rxInterval > 0;
-#endif
-
-    atomic {
-      if (m_state == S_TX_CANCEL) {
-        call SFLUSHTX.strobe();
-        releaseSpiResource();
-        call CSN.set();
-        if (signalSendDone) {
-          signalDone(ECANCEL);
-        } else {
-          m_state = S_STARTED;
-        }
-        return;
-      }
-      
-      
-      call CSN.clr();
-      
-      if(continuousModulation) {
-        /*
-         * We do a complex backoff like this because the last message of a
-         * continuous modulation delivery is currently reloaded into the 
-         * SPI bus and sent off without CCA.  This leaves a small quiet gap
-         * between the continuous modulation and its last message that other
-         * transmitters are guaranteed to hit.
-         *
-         * In the future, when the CRC is built into the continuous delivery
-         * message, this complex backoff may not be needed.  Alternatively,
-         * directly accessing the TXFIFO RAM and adjusting the FCF to 
-         * request an acknowledgement, and then resend without CCA will 
-         * decrease the quiet gap.
-         */
-        if(totalCcaChecks < 20) {
-          if(call CCA.get()) {
-            // Extended backoff
-            totalCcaChecks++;
-          } else {
-            // Saw another transmitter, start over
-            totalCcaChecks = 0;
-          }
-          
-          call CSN.set();
-          releaseSpiResource();
-          signal RadioBackoff.requestInitialBackoff(m_msg);       
-          call BackoffTimer.start( myInitialBackoff );
-          return;
-        }
-        
-        call MDMCTRL1.write(2 << CC2420_MDMCTRL1_TX_MODE);
-      } else {
-        call MDMCTRL1.write(0 << CC2420_MDMCTRL1_TX_MODE);
-      }
-
-      status = m_cca ? call STXONCCA.strobe() : call STXON.strobe();
-      if ( !( status & CC2420_STATUS_TX_ACTIVE ) ) {
-        status = call SNOP.strobe();
-        if ( status & CC2420_STATUS_TX_ACTIVE ) {
-          congestion = FALSE;
-          
-          if(continuousModulation) {
-            post startLplTimer();
-          }
-        }
-      }
-      
-      m_state = congestion ? S_SAMPLE_CCA : S_SFD;
-      call CSN.set();
-    }
-    
-    if ( congestion ) {
-      totalCcaChecks = 0;
-      releaseSpiResource();
-      congestionBackoff();
-    } else {
-      call BackoffTimer.start(CC2420_ABORT_PERIOD);
-    }
-  }
-  
-  
-  /**  
-   * Congestion Backoff
-   */
-  void congestionBackoff() {
-    atomic {
-      if((call CC2420Packet.getMetadata(m_msg))->rxInterval > 0) {
-        signal RadioBackoff.requestLplBackoff(m_msg);
-        call BackoffTimer.start(myLplBackoff);
-        
-      } else {
-        signal RadioBackoff.requestCongestionBackoff(m_msg);
-        call BackoffTimer.start(myCongestionBackoff);
-      }
-    }
-  }
-  
-  error_t acquireSpiResource() {
-    error_t error = call SpiResource.immediateRequest();
-    if ( error != SUCCESS ) {
-      call SpiResource.request();
-    }
-    return error;
-  }
-
-  error_t releaseSpiResource() {
-    call SpiResource.release();
-    return SUCCESS;
-  }
-
-
-  /** 
-   * Setup the packet transmission power and load the tx fifo buffer on
-   * the chip with our outbound packet.  
-   *
-   * Warning: the tx_power metadata might not be initialized and
-   * could be a value other than 0 on boot.  Verification is needed here
-   * to make sure the value won't overstep its bounds in the TXCTRL register
-   * and is transmitting at max power by default.
-   *
-   * It should be possible to manually calculate the packet's CRC here and
-   * tack it onto the end of the header + payload when loading into the TXFIFO,
-   * so the continuous modulation low power listening strategy will continually
-   * deliver valid packets.  This would increase receive reliability for
-   * mobile nodes and lossy connections.  The crcByte() function should use
-   * the same CRC polynomial as the CC2420's AUTOCRC functionality.
-   */
-  void loadTXFIFO() {
-    cc2420_header_t* header = call CC2420Packet.getHeader( m_msg );
-    uint8_t tx_power = (call CC2420Packet.getMetadata( m_msg ))->tx_power;
-    
-    if ( !tx_power ) {
-      // If our packet's tx_power wasn't configured to anything but 0,
-      // send it using the default RF power.  This assumes the
-      // packet's metadata is all set to 0's on boot.
-      
-      tx_power = CC2420_DEF_RFPOWER;
-    }
-    
-    call CSN.clr();
-    
-    if ( m_tx_power != tx_power ) {
-      call TXCTRL.write( ( 2 << CC2420_TXCTRL_TXMIXBUF_CUR ) |
-                         ( 3 << CC2420_TXCTRL_PA_CURRENT ) |
-                         ( 1 << CC2420_TXCTRL_RESERVED ) |
-                         ( (tx_power & 0x1F) << CC2420_TXCTRL_PA_LEVEL ) );
-    }
-    
-    m_tx_power = tx_power;
-    
-    call TXFIFO.write( (uint8_t*)header, header->length - 1 );
-  }
-  
-  void signalDone( error_t err ) {
-    atomic m_state = S_STARTED;
-    signal Send.sendDone( m_msg, err );
-  }
-  
-  
-  
-  /***************** Tasks ****************/
-  task void startLplTimer() {
-    call LplDisableTimer.startOneShot((call CC2420Packet.getMetadata( m_msg ))->rxInterval + 10);
-  }
-
-  /***************** Defaults ****************/
-  default async event void TimeStamp.transmittedSFD( uint16_t time, message_t* p_msg ) {
-  }
-  
-  default async event void TimeStamp.receivedSFD( uint16_t time ) {
-  }
-
-}
-
diff --git a/tos/chips/cc2420/IEEE802154.h b/tos/chips/cc2420/IEEE802154.h
deleted file mode 100644 (file)
index 6329034..0000000
+++ /dev/null
@@ -1,61 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Arch Rock Corporation
- * All rights reserved.
- *
- * 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 the Arch Rock Corporation 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
- * ARCHED ROCK OR ITS 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
- *
- * @author Jonathan Hui <jhui@archrock.com>
- * @version $Revision$ $Date$
- */
-
-#ifndef __IEEE802154_H__
-#define __IEEE802154_H__
-
-enum ieee154_fcf_enums {
-  IEEE154_FCF_FRAME_TYPE = 0,
-  IEEE154_FCF_SECURITY_ENABLED = 3,
-  IEEE154_FCF_FRAME_PENDING = 4,
-  IEEE154_FCF_ACK_REQ = 5,
-  IEEE154_FCF_INTRAPAN = 6,
-  IEEE154_FCF_DEST_ADDR_MODE = 10,
-  IEEE154_FCF_SRC_ADDR_MODE = 14,
-};
-
-enum ieee154_fcf_type_enums {
-  IEEE154_TYPE_BEACON = 0,
-  IEEE154_TYPE_DATA = 1,
-  IEEE154_TYPE_ACK = 2,
-  IEEE154_TYPE_MAC_CMD = 3,
-};
-
-enum iee154_fcf_addr_mode_enums {
-  IEEE154_ADDR_NONE = 0,
-  IEEE154_ADDR_SHORT = 2,
-  IEEE154_ADDR_EXT = 3,
-};
-
-#endif
diff --git a/tos/chips/cc2420/PacketLink.nc b/tos/chips/cc2420/PacketLink.nc
deleted file mode 100644 (file)
index 0b8e54a..0000000
+++ /dev/null
@@ -1,72 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS 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
- */
-/**
- * @author David Moss
- * @author Jon Wyant
- */
-
-interface PacketLink {
-
-  /**
-   * Set the maximum number of times attempt message delivery
-   * Default is 0
-   * @param msg
-   * @param maxRetries the maximum number of attempts to deliver
-   *     the message
-   */
-  command void setRetries(message_t *msg, uint16_t maxRetries);
-
-  /**
-   * Set a delay between each retry attempt
-   * @param msg
-   * @param retryDelay the delay betweeen retry attempts, in milliseconds
-   */
-  command void setRetryDelay(message_t *msg, uint16_t retryDelay);
-
-  /** 
-   * @return the maximum number of retry attempts for this message
-   */
-  command uint16_t getRetries(message_t *msg);
-
-  /**
-   * @return the delay between retry attempts in ms for this message
-   */
-  command uint16_t getRetryDelay(message_t *msg);
-
-  /**
-   * @return TRUE if the message was delivered.
-   */
-  command bool wasDelivered(message_t *msg);
-
-}
-
-
diff --git a/tos/chips/cc2420/PacketLinkC.nc b/tos/chips/cc2420/PacketLinkC.nc
deleted file mode 100644 (file)
index 2b5280c..0000000
+++ /dev/null
@@ -1,70 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS 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
- */
-
-/**
- * Reliable Packet Link Functionality
- * @author David Moss
- * @author Jon Wyant
- */
-
-#warning "*** USING PACKET LINK LAYER"
-
-configuration PacketLinkC {
-  provides {
-    interface Send;
-    interface PacketLink;
-  }
-  
-  uses {
-    interface Send as SubSend;
-  }
-}
-
-implementation {
-
-  components PacketLinkP,
-      ActiveMessageC,
-      CC2420PacketC,
-      RandomC,
-      new StateC() as SendStateC,
-      new TimerMilliC() as DelayTimerC;
-  
-  PacketLink = PacketLinkP;
-  Send = PacketLinkP.Send;
-  SubSend = PacketLinkP.SubSend;
-  
-  PacketLinkP.SendState -> SendStateC;
-  PacketLinkP.DelayTimer -> DelayTimerC;
-  PacketLinkP.PacketAcknowledgements -> ActiveMessageC;
-  PacketLinkP.AMPacket -> ActiveMessageC;
-  PacketLinkP.CC2420Packet -> CC2420PacketC;
-
-}
diff --git a/tos/chips/cc2420/PacketLinkDummyC.nc b/tos/chips/cc2420/PacketLinkDummyC.nc
deleted file mode 100644 (file)
index 2ea159c..0000000
+++ /dev/null
@@ -1,59 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS 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
- */
-
-/**
- * Dummy configuration for PacketLink Layer
- * @author David Moss
- * @author Jon Wyant
- */
-configuration PacketLinkDummyC {
-  provides {
-    interface Send;
-    interface PacketLink;
-  }
-  
-  uses {
-    interface Send as SubSend;
-  }
-}
-
-implementation {
-  components PacketLinkDummyP,
-      ActiveMessageC;
-  
-  PacketLink = PacketLinkDummyP;
-  Send = SubSend;
-  
-  PacketLinkDummyP.PacketAcknowledgements -> ActiveMessageC;
-  
-}
-
diff --git a/tos/chips/cc2420/PacketLinkDummyP.nc b/tos/chips/cc2420/PacketLinkDummyP.nc
deleted file mode 100644 (file)
index 1688da6..0000000
+++ /dev/null
@@ -1,92 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS 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
- */
-
-/**
- * Dummy module for Packet Link layer
- * @author David Moss
- * @author Jon Wyant
- */
-
-module PacketLinkDummyP {
-  provides {
-    interface PacketLink;
-  }
-  
-  uses {
-    interface PacketAcknowledgements;
-  }
-}
-
-implementation {
-  
-  /***************** PacketLink Commands ***************/
-  /**
-   * Set the maximum number of times attempt message delivery
-   * Default is 0
-   * @param msg
-   * @param maxRetries the maximum number of attempts to deliver
-   *     the message
-   */
-  command void PacketLink.setRetries(message_t *msg, uint16_t maxRetries) {
-  }
-
-  /**
-   * Set a delay between each retry attempt
-   * @param msg
-   * @param retryDelay the delay betweeen retry attempts, in milliseconds
-   */
-  command void PacketLink.setRetryDelay(message_t *msg, uint16_t retryDelay) {
-  }
-
-  /** 
-   * @return the maximum number of retry attempts for this message
-   */
-  command uint16_t PacketLink.getRetries(message_t *msg) {
-    return 0;
-  }
-
-  /**
-   * @return the delay between retry attempts in ms for this message
-   */
-  command uint16_t PacketLink.getRetryDelay(message_t *msg) {
-    return 0;
-  }
-
-  /**
-   * @return TRUE if the message was delivered.
-   *     This should always be TRUE if the message was sent to the
-   *     AM_BROADCAST_ADDR
-   */
-  command bool PacketLink.wasDelivered(message_t *msg) {
-    return call PacketAcknowledgements.wasAcked(msg);
-  }
-}
-
diff --git a/tos/chips/cc2420/PacketLinkP.nc b/tos/chips/cc2420/PacketLinkP.nc
deleted file mode 100644 (file)
index cccd212..0000000
+++ /dev/null
@@ -1,228 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS 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
- */
-
-/**
- * Reliable Packet Link Functionality
- * @author David Moss
- * @author Jon Wyant
- */
-#include "CC2420.h"
-
-module PacketLinkP {
-  provides {
-    interface Send;
-    interface PacketLink;
-  }
-  
-  uses {
-    interface Send as SubSend;
-    interface State as SendState;
-    interface PacketAcknowledgements;
-    interface Timer<TMilli> as DelayTimer;
-    interface AMPacket;
-    interface CC2420Packet;
-  }
-}
-
-implementation {
-  
-  /** The message currently being sent */
-  message_t *currentSendMsg;
-  
-  /** Length of the current send message */
-  uint8_t currentSendLen;
-  
-  /** The length of the current send message */
-  uint16_t totalRetries;
-  
-  
-  /**
-   * Send States
-   */
-  enum {
-    S_IDLE,
-    S_SENDING,
-  };
-  
-  
-  /***************** Prototypes ***************/
-  task void send();
-  void signalDone(error_t error);
-    
-  /***************** PacketLink Commands ***************/
-  /**
-   * Set the maximum number of times attempt message delivery
-   * Default is 0
-   * @param msg
-   * @param maxRetries the maximum number of attempts to deliver
-   *     the message
-   */
-  command void PacketLink.setRetries(message_t *msg, uint16_t maxRetries) {
-    (call CC2420Packet.getMetadata(msg))->maxRetries = maxRetries;
-  }
-
-  /**
-   * Set a delay between each retry attempt
-   * @param msg
-   * @param retryDelay the delay betweeen retry attempts, in milliseconds
-   */
-  command void PacketLink.setRetryDelay(message_t *msg, uint16_t retryDelay) {
-    (call CC2420Packet.getMetadata(msg))->retryDelay = retryDelay;
-  }
-
-  /** 
-   * @return the maximum number of retry attempts for this message
-   */
-  command uint16_t PacketLink.getRetries(message_t *msg) {
-    return (call CC2420Packet.getMetadata(msg))->maxRetries;
-  }
-
-  /**
-   * @return the delay between retry attempts in ms for this message
-   */
-  command uint16_t PacketLink.getRetryDelay(message_t *msg) {
-    return (call CC2420Packet.getMetadata(msg))->retryDelay;
-  }
-
-  /**
-   * @return TRUE if the message was delivered.
-   */
-  command bool PacketLink.wasDelivered(message_t *msg) {
-    return call PacketAcknowledgements.wasAcked(msg);
-  }
-  
-  /***************** Send Commands ***************/
-  /**
-   * Each call to this send command gives the message a single
-   * DSN that does not change for every copy of the message
-   * sent out.  For messages that are not acknowledged, such as
-   * a broadcast address message, the receiving end does not
-   * signal receive() more than once for that message.
-   */
-  command error_t Send.send(message_t *msg, uint8_t len) {
-    error_t error;
-    if(call SendState.requestState(S_SENDING) == SUCCESS) {
-    
-      currentSendMsg = msg;
-      currentSendLen = len;
-      totalRetries = 0;
-
-      if(call PacketLink.getRetries(msg) > 0) {
-        call PacketAcknowledgements.requestAck(msg);
-      }
-      
-      if((error = call SubSend.send(msg, len)) != SUCCESS) {    
-        call SendState.toIdle();
-      }
-      
-      return error;
-    }
-    
-    return EBUSY;
-  }
-
-  command error_t Send.cancel(message_t *msg) {
-    if(currentSendMsg == msg) {
-      call SendState.toIdle();
-      return call SubSend.cancel(msg);
-    }
-    
-    return FAIL;
-  }
-  
-  
-  command uint8_t Send.maxPayloadLength() {
-    return call SubSend.maxPayloadLength();
-  }
-
-  command void *Send.getPayload(message_t* msg) {
-    return call SubSend.getPayload(msg);
-  }
-  
-  
-  /***************** SubSend Events ***************/
-  event void SubSend.sendDone(message_t* msg, error_t error) {
-    if(call SendState.getState() == S_SENDING) {
-      totalRetries++;
-      if(call PacketAcknowledgements.wasAcked(msg)) {
-        signalDone(SUCCESS);
-        return;
-        
-      } else if(totalRetries < call PacketLink.getRetries(currentSendMsg)) {
-        
-        if(call PacketLink.getRetryDelay(currentSendMsg) > 0) {
-          // Resend after some delay
-          call DelayTimer.startOneShot(call PacketLink.getRetryDelay(currentSendMsg));
-          
-        } else {
-          // Resend immediately
-          post send();
-        }
-        
-        return;
-      }
-    }
-    
-    signalDone(error);
-  }
-  
-  
-  /***************** Timer Events ****************/  
-  /**
-   * When this timer is running, that means we're sending repeating messages
-   * to a node that is receive check duty cycling.
-   */
-  event void DelayTimer.fired() {
-    if(call SendState.getState() == S_SENDING) {
-      post send();
-    }
-  }
-  
-  /***************** Tasks ***************/
-  task void send() {
-    if(call PacketLink.getRetries(currentSendMsg) > 0) {
-      call PacketAcknowledgements.requestAck(currentSendMsg);
-    }
-    
-    if(call SubSend.send(currentSendMsg, currentSendLen) != SUCCESS) {
-      post send();
-    }
-  }
-  
-  /***************** Functions ***************/  
-  void signalDone(error_t error) {
-    call DelayTimer.stop();
-    call SendState.toIdle();
-    signal Send.sendDone(currentSendMsg, error);
-  }
-}
-
diff --git a/tos/chips/cc2420/README.txt b/tos/chips/cc2420/README.txt
deleted file mode 100644 (file)
index edd2459..0000000
+++ /dev/null
@@ -1,64 +0,0 @@
-
-CC2420 Release Notes 4/11/07
-
-This CC2420 stack contains two low power listening strategies,
-a packet retransmission layer, unique send and receive layers,
-ability to specify backoff and use of clear channel assessments
-on outbound messages, direct RSSI readings, ability to change 
-channels on the fly, an experimental 6LowPAN layer (not
-implemented by default), general bug fixes, and more.
-
-
-Known Issues
-__________________________________________
- > LPL Lockups when the node is also accessing the USART.
-   This is a SPI bus issue, where shutting off the SPI
-   bus in the middle of an operation may cause the node
-   to hang.  Look to future versions on CVS for the fix.
-
- > NoAck LPL doesn't ack at the end properly, and also isn't
-   finished being implemented. The CRC of the packet needs to 
-   manually be loaded into TXFIFO before continuous modulation.
-
- > LPL stack is optimized for reliability at this point, since
-   SFD sampling is not implemented in this version.  
-
-Low Power Listening Schemes and Preprocessor Variables
-__________________________________________
-There are two low power listening schemes.  
-The default is called "AckLpl", because it inserts acknowledgement gaps and
-short backoffs during the packet retransmission process. 
-This allows the transmitter to stop transmitting early, but increases the 
-power consumption per receive check.  This is better for slow receive
-check, high transmission rate networks.
-
-The second is called "NoAckLpl", because it does not insert acknowledgement
-gaps or backoffs in the retransmission process, so the receive checks are 
-shorter but the transmissions are longer.  This is more experimental than
-the Ack LPL version.  The radio continuously modulates the channel when
-delivering its packetized preamble.  This is better for fast receive check,
-low transmission rate networks.
-
-To compile in the default Ack LPL version, #define the preprocessor variable:
-  LOW_POWER_LISTENING
- -or-  
-  ACK_LOW_POWER_LISTENING (default)
-  
-
-To compile in experimental NoAck LPL w/continuous modulation, #define:
-  NOACK_LOW_POWER_LISTENING
-
-  
-To compile in the PacketLink (auto-retransmission) layer, #define:
-  PACKET_LINK
-  
-
-To remove all acknowledgements, #define:
-  CC2420_NO_ACKNOWLEDGEMENTS
-  
-
-To use hardware auto-acks instead of software acks, #define:
-  CC2420_HW_ACKNOWLEDGEMENTS
-
-
diff --git a/tos/chips/cc2420/RadioBackoff.nc b/tos/chips/cc2420/RadioBackoff.nc
deleted file mode 100644 (file)
index 98d6382..0000000
+++ /dev/null
@@ -1,96 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS 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
- */
-/**
- * Interface to request and specify backoff periods for messages
- * @author David Moss
- */
-interface RadioBackoff {
-
-  /**
-   * Must be called within a requestInitialBackoff event
-   * @param backoffTime the amount of time in some unspecified units to backoff
-   */
-  async command void setInitialBackoff(uint16_t backoffTime);
-  
-  /**
-   * Must be called within a requestCongestionBackoff event
-   * @param backoffTime the amount of time in some unspecified units to backoff
-   */
-  async command void setCongestionBackoff(uint16_t backoffTime);
-  
-  
-  /**
-   * Must be called within a requestLplBackoff event
-   * @param backoffTime the amount of time in some unspecified units to backoff
-   */
-  async command void setLplBackoff(uint16_t backoffTime);
-
-
-  /**
-   * Enable CCA for the outbound packet.  Must be called within a requestCca
-   * event
-   * @param ccaOn TRUE to enable CCA, which is the default.
-   */
-  async command void setCca(bool ccaOn);
-
-
-  /**  
-   * Request for input on the initial backoff
-   * Reply using setInitialBackoff(..)
-   * @param msg pointer to the message being sent
-   */
-  async event void requestInitialBackoff(message_t *msg);
-  
-  /**
-   * Request for input on the congestion backoff
-   * Reply using setCongestionBackoff(..)
-   * @param msg pointer to the message being sent
-   */
-  async event void requestCongestionBackoff(message_t *msg);
-  
-  /**
-   * Request for input on the low power listening backoff
-   * This should be somewhat random, but as short as possible
-   * Reply using setLplBackoff(..)
-   * @param msg pointer to the message being sent
-   */
-  async event void requestLplBackoff(message_t *msg);
-  
-  /**
-   * Request for input on whether or not to use CCA on the outbound packet.
-   * Replies should come in the form of setCca(..)
-   * @param msg pointer to the message being sent
-   */
-  async event void requestCca(message_t *msg);
-}
-
diff --git a/tos/chips/cc2420/UniqueReceiveC.nc b/tos/chips/cc2420/UniqueReceiveC.nc
deleted file mode 100644 (file)
index 2a8dd9a..0000000
+++ /dev/null
@@ -1,65 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
- * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
- * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
- * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
- * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
- * OF THE POSSIBILITY OF SUCH DAMAGE
- */
-/**
- * This layer keeps a history of the past RECEIVE_HISTORY_SIZE received messages
- * If the source address and dsn number of a newly received message matches
- * our recent history, we drop the message because we've already seen it.
- * This should sit at the bottom of the stack
- * @author David Moss
- */
-configuration UniqueReceiveC {
-  provides {
-    interface Receive;
-    interface Receive as DuplicateReceive;
-  }
-  
-  uses {
-    interface Receive as SubReceive;
-  }
-}
-
-implementation {
-  components UniqueReceiveP,
-      CC2420PacketC,
-      MainC;
-  
-  Receive = UniqueReceiveP.Receive;
-  DuplicateReceive = UniqueReceiveP.DuplicateReceive;
-  SubReceive = UniqueReceiveP.SubReceive;
-      
-  MainC.SoftwareInit -> UniqueReceiveP;
-  
-  UniqueReceiveP.CC2420Packet -> CC2420PacketC;
-  
-}
-
diff --git a/tos/chips/cc2420/UniqueReceiveP.nc b/tos/chips/cc2420/UniqueReceiveP.nc
deleted file mode 100644 (file)
index fb63ec6..0000000
+++ /dev/null
@@ -1,181 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
- * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
- * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
- * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
- * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
- * OF THE POSSIBILITY OF SUCH DAMAGE
- */
-/** 
- * This layer keeps a history of the past RECEIVE_HISTORY_SIZE received messages
- * If the source address and dsn number of a newly received message matches
- * our recent history, we drop the message because we've already seen it.
- * @author David Moss
- */
-#include "CC2420.h"
-
-module UniqueReceiveP {
-  provides {
-    interface Receive;
-    interface Receive as DuplicateReceive;
-    interface Init;
-  }
-  
-  uses {
-    interface Receive as SubReceive;
-    interface CC2420Packet;
-  }
-}
-
-implementation {
-  
-  struct {
-    am_addr_t source;
-    uint8_t dsn;
-  } receivedMessages[RECEIVE_HISTORY_SIZE];
-  
-  uint8_t writeIndex = 0;
-  
-  /** History element containing info on a source previously received from */
-  uint8_t recycleSourceElement;
-  
-  enum {
-    INVALID_ELEMENT = 0xFF,
-  };
-  
-  /***************** Init Commands *****************/
-  command error_t Init.init() {
-    int i;
-    for(i = 0; i < RECEIVE_HISTORY_SIZE; i++) {
-      receivedMessages[i].source = (am_addr_t) 0xFFFF;
-      receivedMessages[i].dsn = 0;
-    }
-    return SUCCESS;
-  }
-  
-  /***************** Prototypes Commands ***************/
-  bool hasSeen(uint16_t msgSource, uint8_t msgDsn);
-  void insert(uint16_t msgSource, uint8_t msgDsn);
-  
-  /***************** Receive Commands ***************/
-  command void *Receive.getPayload(message_t* msg, uint8_t* len) {
-    return call SubReceive.getPayload(msg, len);
-  }
-
-  command uint8_t Receive.payloadLength(message_t* msg) {
-    return call SubReceive.payloadLength(msg);
-  }
-  
-  
-  /***************** DuplicateReceive Commands ****************/
-  command void *DuplicateReceive.getPayload(message_t* msg, uint8_t* len) {
-    return call SubReceive.getPayload(msg, len);
-  }
-
-  command uint8_t DuplicateReceive.payloadLength(message_t* msg) {
-    return call SubReceive.payloadLength(msg);
-  }
-  
-  /***************** SubReceive Events *****************/
-  event message_t *SubReceive.receive(message_t* msg, void* payload, 
-      uint8_t len) {
-    uint16_t msgSource = (call CC2420Packet.getHeader(msg))->src;
-    uint8_t msgDsn = (call CC2420Packet.getHeader(msg))->dsn;
-    
-    if(hasSeen(msgSource, msgDsn)) {
-      return signal DuplicateReceive.receive(msg, payload, len);
-      
-    } else {
-      insert(msgSource, msgDsn);
-      return signal Receive.receive(msg, payload, len);
-    }
-  }
-  
-  /****************** Functions ****************/  
-  /**
-   * This function does two things:
-   *  1. It loops through our entire receive history and detects if we've 
-   *     seen this DSN before from the given source (duplicate packet)
-   *  2. It detects if we've seen messages from this source before, so we know
-   *     where to update our history if it turns out this is a new message.
-   *
-   * The global recycleSourceElement variable stores the location of the next insert
-   * if we've received a packet from that source before.  Otherwise, it's up 
-   * to the insert() function to decide who to kick out of our history.
-   */
-  bool hasSeen(uint16_t msgSource, uint8_t msgDsn) {
-    int i;
-    recycleSourceElement = INVALID_ELEMENT;
-    
-    atomic {
-      for(i = 0; i < RECEIVE_HISTORY_SIZE; i++) {
-        if(receivedMessages[i].source == msgSource) {
-          if(receivedMessages[i].dsn == msgDsn) {
-            // Only exit this loop if we found a duplicate packet
-            return TRUE;
-          }
-          
-          recycleSourceElement = i;
-        }
-      }
-    }
-      
-    return FALSE;
-  }
-  
-  /**
-   * Insert the message into the history.  If we received a message from this
-   * source before, insert it into the same location as last time and verify
-   * that the "writeIndex" is not pointing to that location. Otherwise,
-   * insert it into the "writeIndex" location.
-   */
-  void insert(uint16_t msgSource, uint8_t msgDsn) {
-    uint8_t element = recycleSourceElement;
-    bool increment = FALSE;
-   
-    atomic {
-      if(element == INVALID_ELEMENT || writeIndex == element) {
-        // Use the writeIndex element to insert this new message into
-        element = writeIndex;
-        increment = TRUE;
-      }
-
-      receivedMessages[element].source = msgSource;
-      receivedMessages[element].dsn = msgDsn;
-      if(increment) {
-        writeIndex++;
-        writeIndex %= RECEIVE_HISTORY_SIZE;
-      }
-    }
-  }
-  
-  /***************** Defaults ****************/
-  default event message_t *DuplicateReceive.receive(message_t *msg, void *payload, uint8_t len) {
-    return msg;
-  }
-}
-
diff --git a/tos/chips/cc2420/UniqueSendC.nc b/tos/chips/cc2420/UniqueSendC.nc
deleted file mode 100644 (file)
index a2cbcef..0000000
+++ /dev/null
@@ -1,65 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS 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
- */
-/**
- * Generate a unique dsn byte for this outgoing packet
- * This should sit at the top of the stack
- * @author David Moss
- */
-configuration UniqueSendC {
-  provides {
-    interface Send;
-  }
-  
-  uses {
-    interface Send as SubSend;
-  }
-}
-
-implementation {
-  components UniqueSendP,
-      new StateC(),
-      RandomC,
-      CC2420PacketC,
-      MainC;
-      
-  Send = UniqueSendP.Send;
-  SubSend = UniqueSendP.SubSend;
-  
-  MainC.SoftwareInit -> UniqueSendP;
-  
-  UniqueSendP.State -> StateC;
-  UniqueSendP.Random -> RandomC;
-  UniqueSendP.CC2420Packet -> CC2420PacketC;
-  
-}
-
diff --git a/tos/chips/cc2420/UniqueSendP.nc b/tos/chips/cc2420/UniqueSendP.nc
deleted file mode 100644 (file)
index 74df958..0000000
+++ /dev/null
@@ -1,110 +0,0 @@
-/*
- * Copyright (c) 2005-2006 Rincon Research Corporation
- * All rights reserved.
- *
- * 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 the Rincon Research Corporation 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
- * RINCON RESEARCH OR ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
- * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
- * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
- * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
- * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
- * OF THE POSSIBILITY OF SUCH DAMAGE
- */
-/**
- * This layer is responsible for supplying a unique data sequence number (dsn)
- * to each outgoing message.
- * @author David Moss
- */
-module UniqueSendP {
-  provides {
-    interface Send;
-    interface Init;
-  }
-  
-  uses {
-    interface Send as SubSend;
-    interface State;
-    interface Random;
-    interface CC2420Packet;
-  }
-}
-
-implementation {
-
-  uint8_t localSendId;
-  
-  enum {
-    S_IDLE,
-    S_SENDING,
-  };
-  
-  /***************** Init Commands ****************/
-  command error_t Init.init() {
-    localSendId = call Random.rand16();
-    return SUCCESS;
-  }
-
-  /***************** Send Commands ****************/
-  /**
-   * Each call to this send command gives the message a single
-   * DSN that does not change for every copy of the message
-   * sent out.  For messages that are not acknowledged, such as
-   * a broadcast address message, the receiving end does not
-   * signal receive() more than once for that message.
-   */
-  command error_t Send.send(message_t *msg, uint8_t len) {
-    error_t error;
-    if(call State.requestState(S_SENDING) == SUCCESS) {
-      (call CC2420Packet.getHeader(msg))->dsn = localSendId++;
-      
-      if((error = call SubSend.send(msg, len)) != SUCCESS) {
-        call State.toIdle();
-      }
-      
-      return error;
-    }
-    
-    return EBUSY;
-  }
-
-  command error_t Send.cancel(message_t *msg) {
-    return call SubSend.cancel(msg);
-  }
-  
-  
-  command uint8_t Send.maxPayloadLength() {
-    return call SubSend.maxPayloadLength();
-  }
-
-  command void *Send.getPayload(message_t* msg) {
-    return call SubSend.getPayload(msg);
-  }
-  
-  /***************** SubSend Events ****************/
-  event void SubSend.sendDone(message_t *msg, error_t error) {
-    call State.toIdle();
-    signal Send.sendDone(msg, error);
-  }
-  
-}
-