]> oss.titaniummirror.com Git - tinyos-2.x.git/commitdiff
change metadata handling,
authormmaroti <mmaroti>
Thu, 2 Apr 2009 22:09:59 +0000 (22:09 +0000)
committermmaroti <mmaroti>
Thu, 2 Apr 2009 22:09:59 +0000 (22:09 +0000)
remove the RF2xxPacket component, move functionality to RF2xxActiveMessage,
prepare blip support (RF2xxMessageC)

56 files changed:
apps/tests/rf230/RF230Sniffer/RF230SnifferC.nc
tos/chips/rf2xx/layers/DummyLayerC.nc
tos/chips/rf2xx/layers/DummyLayerP.nc [deleted file]
tos/chips/rf2xx/layers/IEEE154NetworkLayerC.nc
tos/chips/rf2xx/layers/IEEE154NetworkLayerP.nc
tos/chips/rf2xx/layers/IEEE154PacketLayer.h [new file with mode: 0644]
tos/chips/rf2xx/layers/IEEE154PacketLayer.nc [new file with mode: 0644]
tos/chips/rf2xx/layers/IEEE154PacketLayerC.nc [new file with mode: 0644]
tos/chips/rf2xx/layers/IEEE154PacketLayerP.nc [new file with mode: 0644]
tos/chips/rf2xx/layers/LowPowerListeningDummyC.nc [new file with mode: 0644]
tos/chips/rf2xx/layers/LowPowerListeningDummyP.nc [new file with mode: 0644]
tos/chips/rf2xx/layers/LowPowerListeningLayer.h [new file with mode: 0644]
tos/chips/rf2xx/layers/LowPowerListeningLayerC.nc
tos/chips/rf2xx/layers/LowPowerListeningLayerP.nc
tos/chips/rf2xx/layers/MetadataFlagsLayer.h [new file with mode: 0644]
tos/chips/rf2xx/layers/MetadataFlagsLayerC.nc [new file with mode: 0644]
tos/chips/rf2xx/layers/PacketLinkLayer.h
tos/chips/rf2xx/layers/PacketLinkLayerC.nc
tos/chips/rf2xx/layers/PacketLinkLayerP.nc
tos/chips/rf2xx/layers/SoftwareAckConfig.nc
tos/chips/rf2xx/layers/SoftwareAckLayerC.nc
tos/chips/rf2xx/layers/SoftwareAckLayerP.nc
tos/chips/rf2xx/layers/TimeStampingLayer.h [new file with mode: 0644]
tos/chips/rf2xx/layers/TimeStampingLayerC.nc [new file with mode: 0644]
tos/chips/rf2xx/layers/TimeStampingLayerP.nc [new file with mode: 0644]
tos/chips/rf2xx/rf212/RF212.h [deleted file]
tos/chips/rf2xx/rf212/RF212ActiveMessage.h [new file with mode: 0644]
tos/chips/rf2xx/rf212/RF212ActiveMessageC.nc
tos/chips/rf2xx/rf212/RF212ActiveMessageP.nc
tos/chips/rf2xx/rf212/RF212DriverLayer.h [new file with mode: 0644]
tos/chips/rf2xx/rf212/RF212DriverLayerC.nc
tos/chips/rf2xx/rf212/RF212DriverLayerP.nc
tos/chips/rf2xx/rf212/RF212Packet.h [deleted file]
tos/chips/rf2xx/rf212/RF212PacketC.nc [deleted file]
tos/chips/rf2xx/rf212/RF212PacketP.nc [deleted file]
tos/chips/rf2xx/rf230/RF230.h [deleted file]
tos/chips/rf2xx/rf230/RF230ActiveMessage.h [new file with mode: 0644]
tos/chips/rf2xx/rf230/RF230ActiveMessageC.nc
tos/chips/rf2xx/rf230/RF230ActiveMessageP.nc
tos/chips/rf2xx/rf230/RF230DriverLayer.h [new file with mode: 0644]
tos/chips/rf2xx/rf230/RF230DriverLayerC.nc
tos/chips/rf2xx/rf230/RF230DriverLayerP.nc
tos/chips/rf2xx/rf230/RF230Packet.h [deleted file]
tos/chips/rf2xx/rf230/RF230PacketC.nc [deleted file]
tos/chips/rf2xx/rf230/RF230PacketP.nc [deleted file]
tos/chips/rf2xx/util/IEEE154Packet2.h [deleted file]
tos/chips/rf2xx/util/IEEE154Packet2.nc [deleted file]
tos/chips/rf2xx/util/IEEE154Packet2C.nc [deleted file]
tos/chips/rf2xx/util/IEEE154Packet2P.nc [deleted file]
tos/chips/rf2xx/util/MetadataFlagC.nc [new file with mode: 0644]
tos/chips/rf2xx/util/PacketData.nc
tos/chips/rf2xx/util/PacketFlag.nc [new file with mode: 0644]
tos/platforms/iris/TimeSyncMessageC.nc
tos/platforms/iris/chips/rf230/HplRF230C.nc
tos/platforms/iris/chips/rf230/RadioConfig.h
tos/platforms/iris/platform_message.h

index cf83fb44810c6fbdc789646b093c978f5289f994..ff5abc6045067e55b2d47da0d8f6fab59a179200 100644 (file)
@@ -27,15 +27,26 @@ configuration RF230SnifferC
 
 implementation
 {
-       components RF230SnifferP, MainC, SerialActiveMessageC, RF230DriverLayerC, RF230ActiveMessageP, IEEE154Packet2C, AssertC;
+       components RF230SnifferP, MainC, SerialActiveMessageC, AssertC;
        
        RF230SnifferP.Boot -> MainC;
        RF230SnifferP.SplitControl -> SerialActiveMessageC;
        RF230SnifferP.RadioState -> RF230DriverLayerC;
 
+       components RF230DriverLayerC;
+       RF230DriverLayerC.PacketRF230Metadata -> RF230ActiveMessageP;
        RF230DriverLayerC.RF230DriverConfig -> RF230ActiveMessageP;
+       RF230DriverLayerC.PacketTimeStamp -> TimeStampingLayerC;
 
-       RF230ActiveMessageP.IEEE154Packet2 -> IEEE154Packet2C;
+       components MetadataFlagsLayerC;
+       MetadataFlagsLayerC.PacketFlagsMetadata -> RF230ActiveMessageP;
+
+       components RF230ActiveMessageP, IEEE154PacketLayerC;
+       RF230ActiveMessageP.IEEE154PacketLayer -> IEEE154PacketLayerC;
+
+       components TimeStampingLayerC;
+       TimeStampingLayerC.LocalTimeRadio -> RF230DriverLayerC;
+       TimeStampingLayerC.PacketTimeStampMetadata -> RF230ActiveMessageP;
 
        // just to avoid a timer compilation bug
        components new TimerMilliC();
index e3c55dea3352de88b545b3490f41476b9c34a6ff..3b76025d722aef3e180f5e62e9df2fb5a2dbbd2d 100644 (file)
@@ -28,7 +28,6 @@ generic configuration DummyLayerC()
                interface SplitControl;
                interface Send;
                interface Receive;
-               interface LowPowerListening;
 
                interface RadioState;
                interface RadioSend;
@@ -64,7 +63,4 @@ implementation
        Receive = SubReceive;
 
        Config = UnconnectedConfig;
-
-       components DummyLayerP;
-       LowPowerListening = DummyLayerP.LowPowerListening;
 }
diff --git a/tos/chips/rf2xx/layers/DummyLayerP.nc b/tos/chips/rf2xx/layers/DummyLayerP.nc
deleted file mode 100644 (file)
index 8ce3261..0000000
+++ /dev/null
@@ -1,50 +0,0 @@
-/*
- * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
- * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
- * 
- * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
- * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
- *
- * Author: Miklos Maroti
- */
-
-module DummyLayerP
-{
-       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; }
-}
index 5069218d655a09bc278e0fdb9d1cac980fde7cea..64cb933b43ca22c0ee26bf4eba3c736686973800 100644 (file)
@@ -39,7 +39,7 @@ configuration IEEE154NetworkLayerC
 
 implementation
 {
-       components IEEE154NetworkLayerP, IEEE154Packet2C;
+       components IEEE154NetworkLayerP, IEEE154PacketLayerC;
 
        SplitControl = SubControl;
 
@@ -49,5 +49,5 @@ implementation
        SubSend = IEEE154NetworkLayerP;
        SubReceive = IEEE154NetworkLayerP;
 
-       IEEE154NetworkLayerP.IEEE154Packet2 -> IEEE154Packet2C;
+       IEEE154NetworkLayerP.IEEE154PacketLayer -> IEEE154PacketLayerC;
 }
index 4771f6889200c7def17fa75622a4583c3241355e..d5b33bf73b9743bf163dc9e7d9d4b8d4ba27aa3e 100644 (file)
@@ -35,7 +35,7 @@ module IEEE154NetworkLayerP
                interface Send as SubSend;
                interface Receive as SubReceive;
 
-               interface IEEE154Packet2;
+               interface IEEE154PacketLayer;
        }
 }
 
@@ -47,7 +47,7 @@ implementation
 
        command error_t Send.send(message_t* msg, uint8_t len)
        {
-               call IEEE154Packet2.set6LowPan(msg, TINYOS_6LOWPAN_NETWORK_ID);
+               call IEEE154PacketLayer.set6LowPan(msg, TINYOS_6LOWPAN_NETWORK_ID);
                return call SubSend.send(msg, len);
        }
 
@@ -73,7 +73,7 @@ implementation
   
        event message_t *SubReceive.receive(message_t *msg, void *payload, uint8_t len)
        {
-               uint8_t network = call IEEE154Packet2.get6LowPan(msg);
+               uint8_t network = call IEEE154PacketLayer.get6LowPan(msg);
                if( network == TINYOS_6LOWPAN_NETWORK_ID )
                        return signal Receive.receive(msg, payload, len);
                else
diff --git a/tos/chips/rf2xx/layers/IEEE154PacketLayer.h b/tos/chips/rf2xx/layers/IEEE154PacketLayer.h
new file mode 100644 (file)
index 0000000..721d96d
--- /dev/null
@@ -0,0 +1,75 @@
+/*
+ * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
+ * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ * 
+ * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
+ * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+ *
+ * Author: Miklos Maroti
+ */
+
+#ifndef __IEEE154PACKETLAYER_H__
+#define __IEEE154PACKETLAYER_H__
+
+typedef nx_struct ieee154_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
+#ifndef TFRAMES_ENABLED        
+       nxle_uint8_t network;
+#endif
+
+       nxle_uint8_t type;
+} ieee154_header_t;
+
+// the actual radio driver might not use this
+typedef nx_struct ieee154_footer_t
+{ 
+       nxle_uint16_t crc;
+} ieee154_footer_t;
+
+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,
+       IEEE154_TYPE_MASK = 7,
+};
+
+enum iee154_fcf_addr_mode_enums {
+       IEEE154_ADDR_NONE = 0,
+       IEEE154_ADDR_SHORT = 2,
+       IEEE154_ADDR_EXT = 3,
+       IEEE154_ADDR_MASK = 3,
+};
+
+#endif//__IEEE154PACKETLAYER_H__
diff --git a/tos/chips/rf2xx/layers/IEEE154PacketLayer.nc b/tos/chips/rf2xx/layers/IEEE154PacketLayer.nc
new file mode 100644 (file)
index 0000000..896b9cd
--- /dev/null
@@ -0,0 +1,197 @@
+/*
+ * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
+ * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ * 
+ * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
+ * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+ *
+ * Author: Miklos Maroti
+ */
+
+#include <IEEE154PacketLayer.h>
+#include <message.h>
+
+/**
+ * This interface encapsulates IEEE 802.15.4 intrapan data frames with 
+ * 16-bit destination pan, source and destination addresses. It also 
+ * supports 6LowPan interoperability mode, and acknowledgement frames.
+ * Note, that this interface does not support the CRC-16 value, which
+ * should be verified before the data can be trusted.
+ */
+interface IEEE154PacketLayer
+{
+       /**
+        * Returns the IEEE 802.15.4 header including the length field.
+        */
+       async command ieee154_header_t* getHeader(message_t* msg);
+
+       /**
+        * Returns the raw value (unadjusted) of the length field
+        */
+       async command uint8_t getLength(message_t* msg);
+
+       /**
+        * Sets the length field
+        */
+       async command void setLength(message_t* msg, uint8_t length);
+
+       /**
+        * Returns the frame control field. This method should not be used, 
+        * isDataFrame and isAckFrame should be used instead.
+        */
+       async command uint16_t getFCF(message_t* msg);
+
+       /**
+        * Sets the frame control field. This method should not be used, 
+        * createDataFrame and createAckFrame should be used instead.
+        */
+       async command void setFCF(message_t* msg, uint16_t fcf);
+
+       /**
+        * Returns TRUE if the message is a data frame supported by 
+        * this interface (based on the value of the FCF).
+        */
+       async command bool isDataFrame(message_t* msg);
+
+       /**
+        * Sets the FCF to create a data frame supported by this interface.
+        * You may call setAckRequired and setFramePending commands after this.
+        */
+       async command void createDataFrame(message_t* msg);
+
+       /**
+        * Returns TRUE if the message is an acknowledgement frame supported
+        * by this interface (based on the value of the FCF).
+        */
+       async command bool isAckFrame(message_t* msg);
+
+       /**
+        * Sets the FCF to create an acknowledgement frame supported by
+        * this interface. You may call setFramePending after this.
+        */
+       async command void createAckFrame(message_t* msg);
+
+       /**
+        * Creates an acknowledgement packet for the given data packet.
+        * This also sets the DSN value. The data message must be a 
+        * data frame, the ack message will be overwritten.
+        */
+       async command void createAckReply(message_t* data, message_t* ack);
+
+       /**
+        * Returns TRUE if the acknowledgement packet corresponds to the
+        * data packet. The data message must be a data packet.
+        */
+       async command bool verifyAckReply(message_t* data, message_t* ack);
+
+       /**
+        * Returns TRUE if the ACK required field is set in the FCF.
+        */
+       async command bool getAckRequired(message_t* msg);
+
+       /**
+        * Sets the ACK required field in the FCF, should never be set
+        * for acknowledgement frames.
+        */
+       async command void setAckRequired(message_t* msg, bool ack);
+
+       /**
+        * Returns TRUE if the frame pending field is set in the FCF.
+        */
+       async command bool getFramePending(message_t* msg);
+
+       /**
+        * Sets the frame pending field in the FCF.
+        */
+       async command void setFramePending(message_t* msg, bool pending);
+
+       /**
+        * Returns the data sequence number
+        */
+       async command uint8_t getDSN(message_t* msg);
+
+       /**
+        * Sets the data sequence number
+        */
+       async command void setDSN(message_t* msg, uint8_t dsn);
+
+       /**
+        * returns the destination PAN id, values <= 255 are tinyos groups,
+        * valid only for data frames
+        */
+       async command uint16_t getDestPan(message_t* msg);
+
+       /**
+        * Sets the destination PAN id, valid only for data frames
+        */
+       async command void setDestPan(message_t* msg, uint16_t pan);
+
+       /**
+        * Returns the destination address, valid only for data frames
+        */
+       async command uint16_t getDestAddr(message_t* msg);
+
+       /**
+        * Sets the destination address, valid only for data frames
+        */
+       async command void setDestAddr(message_t* msg, uint16_t addr);
+
+       /**
+        * Returns the source address, valid only for data frames
+        */
+       async command uint16_t getSrcAddr(message_t* msg);
+
+       /**
+        * Sets the source address, valid only for data frames
+        */
+       async command void setSrcAddr(message_t* msg, uint16_t addr);
+
+#ifndef TFRAMES_ENABLED
+
+       /**
+        * Returns the value of the 6LowPan network field.
+        */
+       async command uint8_t get6LowPan(message_t* msg);
+
+       /**
+        * Sets the value of the 6LowPan network field.
+        */
+       async command void set6LowPan(message_t* msg, uint8_t network);
+
+#endif
+
+       /**
+        * Returns the active message type of the message
+        */
+       async command am_id_t getType(message_t* msg);
+
+       /**
+        * Sets the active message type
+        */
+       async command void setType(message_t* msg, am_id_t type);
+
+       /**
+        * Returns TRUE if the packet is a data packet, the ACK_REQ field
+        * is set and the destination address is not the broadcast address.
+        */
+       async command bool requiresAckWait(message_t* msg);
+
+       /**
+        * Returns TRUE if the packet is a data packet, the ACK_REQ field
+        * is set and the destionation address is this node.
+        */
+       async command bool requiresAckReply(message_t* msg);
+}
diff --git a/tos/chips/rf2xx/layers/IEEE154PacketLayerC.nc b/tos/chips/rf2xx/layers/IEEE154PacketLayerC.nc
new file mode 100644 (file)
index 0000000..a0768a9
--- /dev/null
@@ -0,0 +1,40 @@
+/*
+ * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
+ * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ * 
+ * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
+ * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+ *
+ * Author: Miklos Maroti
+ */
+
+configuration IEEE154PacketLayerC
+{
+       provides
+       {
+               interface IEEE154PacketLayer;
+               interface AMPacket;
+       }
+}
+
+implementation
+{
+       components IEEE154PacketLayerP, ActiveMessageAddressC;
+       IEEE154PacketLayerP.ActiveMessageAddress -> ActiveMessageAddressC;
+
+       IEEE154PacketLayer = IEEE154PacketLayerP;
+       AMPacket = IEEE154PacketLayerP;
+}
diff --git a/tos/chips/rf2xx/layers/IEEE154PacketLayerP.nc b/tos/chips/rf2xx/layers/IEEE154PacketLayerP.nc
new file mode 100644 (file)
index 0000000..5857365
--- /dev/null
@@ -0,0 +1,294 @@
+/*
+ * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
+ * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ * 
+ * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
+ * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+ *
+ * Author: Miklos Maroti
+ */
+
+#include <IEEE154PacketLayer.h>
+
+module IEEE154PacketLayerP
+{
+       provides 
+       {
+               interface IEEE154PacketLayer;
+               interface AMPacket;
+       }
+
+       uses interface ActiveMessageAddress;
+}
+
+implementation
+{
+/*----------------- IEEE154Packet -----------------*/
+
+       enum
+       {
+               IEEE154_DATA_FRAME_MASK = (IEEE154_TYPE_MASK << IEEE154_FCF_FRAME_TYPE) 
+                       | (1 << IEEE154_FCF_INTRAPAN) 
+                       | (IEEE154_ADDR_MASK << IEEE154_FCF_DEST_ADDR_MODE) 
+                       | (IEEE154_ADDR_MASK << IEEE154_FCF_SRC_ADDR_MODE),
+
+               IEEE154_DATA_FRAME_VALUE = (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),
+
+               IEEE154_ACK_FRAME_LENGTH = 5,   // includes the FCF, DSN and FCS
+               IEEE154_ACK_FRAME_MASK = (IEEE154_TYPE_MASK << IEEE154_FCF_FRAME_TYPE), 
+               IEEE154_ACK_FRAME_VALUE = (IEEE154_TYPE_ACK << IEEE154_FCF_FRAME_TYPE),
+       };
+
+       inline ieee154_header_t* getHeader(message_t* msg)
+       {
+               return (ieee154_header_t*)(msg->data - sizeof(ieee154_header_t));
+       }
+
+       inline async command ieee154_header_t* IEEE154PacketLayer.getHeader(message_t* msg)
+       {
+               return getHeader(msg);
+       }
+
+       inline async command uint8_t IEEE154PacketLayer.getLength(message_t* msg)
+       {
+               return getHeader(msg)->length;
+       }
+
+       inline async command void IEEE154PacketLayer.setLength(message_t* msg, uint8_t length)
+       {
+               getHeader(msg)->length = length;
+       }
+
+       inline async command uint16_t IEEE154PacketLayer.getFCF(message_t* msg)
+       {
+               return getHeader(msg)->fcf;
+       }
+
+       inline async command void IEEE154PacketLayer.setFCF(message_t* msg, uint16_t fcf)
+       {
+               getHeader(msg)->fcf = fcf;
+       }
+
+       inline async command bool IEEE154PacketLayer.isDataFrame(message_t* msg)
+       {
+               return (getHeader(msg)->fcf & IEEE154_DATA_FRAME_MASK) == IEEE154_DATA_FRAME_VALUE;
+       }
+
+       inline async command void IEEE154PacketLayer.createDataFrame(message_t* msg)
+       {
+               getHeader(msg)->fcf = IEEE154_DATA_FRAME_VALUE;
+       }
+
+       inline async command bool IEEE154PacketLayer.isAckFrame(message_t* msg)
+       {
+               return (getHeader(msg)->fcf & IEEE154_ACK_FRAME_MASK) == IEEE154_ACK_FRAME_VALUE;
+       }
+
+       inline async command void IEEE154PacketLayer.createAckFrame(message_t* msg)
+       {
+               ieee154_header_t* header = getHeader(msg);
+
+               header->length = IEEE154_ACK_FRAME_LENGTH;
+               header->fcf = IEEE154_ACK_FRAME_VALUE;
+       }
+
+       inline async command void IEEE154PacketLayer.createAckReply(message_t* data, message_t* ack)
+       {
+               ieee154_header_t* header = getHeader(ack);
+
+               header->length = IEEE154_ACK_FRAME_LENGTH;
+               header->fcf = IEEE154_ACK_FRAME_VALUE;
+               header->dsn = getHeader(data)->dsn;
+       }
+
+       inline async command bool IEEE154PacketLayer.verifyAckReply(message_t* data, message_t* ack)
+       {
+               ieee154_header_t* header = getHeader(ack);
+
+               return header->dsn == getHeader(data)->dsn
+                       && (header->fcf & IEEE154_ACK_FRAME_MASK) == IEEE154_ACK_FRAME_VALUE;
+       }
+
+       inline async command bool IEEE154PacketLayer.getAckRequired(message_t* msg)
+       {
+               return getHeader(msg)->fcf & (1 << IEEE154_FCF_ACK_REQ);
+       }
+
+       inline async command void IEEE154PacketLayer.setAckRequired(message_t* msg, bool ack)
+       {
+               if( ack )
+                       getHeader(msg)->fcf |= (1 << IEEE154_FCF_ACK_REQ);
+               else
+                       getHeader(msg)->fcf &= ~(uint16_t)(1 << IEEE154_FCF_ACK_REQ);
+       }
+
+       inline async command bool IEEE154PacketLayer.getFramePending(message_t* msg)
+       {
+               return getHeader(msg)->fcf & (1 << IEEE154_FCF_FRAME_PENDING);
+       }
+
+       inline async command void IEEE154PacketLayer.setFramePending(message_t* msg, bool pending)
+       {
+               if( pending )
+                       getHeader(msg)->fcf |= (1 << IEEE154_FCF_FRAME_PENDING);
+               else
+                       getHeader(msg)->fcf &= ~(uint16_t)(1 << IEEE154_FCF_FRAME_PENDING);
+       }
+
+       inline async command uint8_t IEEE154PacketLayer.getDSN(message_t* msg)
+       {
+               return getHeader(msg)->dsn;
+       }
+
+       inline async command void IEEE154PacketLayer.setDSN(message_t* msg, uint8_t dsn)
+       {
+               getHeader(msg)->dsn = dsn;
+       }
+
+       inline async command uint16_t IEEE154PacketLayer.getDestPan(message_t* msg)
+       {
+               return getHeader(msg)->destpan;
+       }
+
+       inline async command void IEEE154PacketLayer.setDestPan(message_t* msg, uint16_t pan)
+       {
+               getHeader(msg)->destpan = pan;
+       }
+
+       inline async command uint16_t IEEE154PacketLayer.getDestAddr(message_t* msg)
+       {
+               return getHeader(msg)->dest;
+       }
+
+       inline async command void IEEE154PacketLayer.setDestAddr(message_t* msg, uint16_t addr)
+       {
+               getHeader(msg)->dest = addr;
+       }
+
+       inline async command uint16_t IEEE154PacketLayer.getSrcAddr(message_t* msg)
+       {
+               return getHeader(msg)->src;
+       }
+
+       inline async command void IEEE154PacketLayer.setSrcAddr(message_t* msg, uint16_t addr)
+       {
+               getHeader(msg)->src = addr;
+       }
+
+#ifndef TFRAMES_ENABLED
+
+       inline async command uint8_t IEEE154PacketLayer.get6LowPan(message_t* msg)
+       {
+               return getHeader(msg)->network;
+       }
+
+       inline async command void IEEE154PacketLayer.set6LowPan(message_t* msg, uint8_t network)
+       {
+               getHeader(msg)->network = network;
+       }
+
+#endif
+
+       inline async command am_id_t IEEE154PacketLayer.getType(message_t* msg)
+       {
+               return getHeader(msg)->type;
+       }
+
+       inline async command void IEEE154PacketLayer.setType(message_t* msg, am_id_t type)
+       {
+               getHeader(msg)->type = type;
+       }
+
+       async command bool IEEE154PacketLayer.requiresAckWait(message_t* msg)
+       {
+               return call IEEE154PacketLayer.getAckRequired(msg)
+                       && call IEEE154PacketLayer.isDataFrame(msg)
+                       && call IEEE154PacketLayer.getDestAddr(msg) != 0xFFFF;
+       }
+
+       async command bool IEEE154PacketLayer.requiresAckReply(message_t* msg)
+       {
+               return call IEEE154PacketLayer.getAckRequired(msg)
+                       && call IEEE154PacketLayer.isDataFrame(msg)
+                       && call IEEE154PacketLayer.getDestAddr(msg) == call ActiveMessageAddress.amAddress();
+       }
+
+       inline async event void ActiveMessageAddress.changed()
+       {
+       }
+
+/*----------------- AMPacket -----------------*/
+
+       inline command am_addr_t AMPacket.address()
+       {
+               return call ActiveMessageAddress.amAddress();
+       }
+       inline command am_group_t AMPacket.localGroup()
+       {
+               // TODO: check if this is correct
+               return call ActiveMessageAddress.amGroup();
+       }
+
+       inline command am_addr_t AMPacket.destination(message_t* msg)
+       {
+               return call IEEE154PacketLayer.getDestAddr(msg);
+       }
+       inline command am_addr_t AMPacket.source(message_t* msg)
+       {
+               return call IEEE154PacketLayer.getSrcAddr(msg);
+       }
+
+       inline command void AMPacket.setDestination(message_t* msg, am_addr_t addr)
+       {
+               call IEEE154PacketLayer.setDestAddr(msg, addr);
+       }
+
+       inline command void AMPacket.setSource(message_t* msg, am_addr_t addr)
+       {
+               call IEEE154PacketLayer.setSrcAddr(msg, addr);
+       }
+
+       inline command bool AMPacket.isForMe(message_t* msg)
+       {
+               am_addr_t addr = call AMPacket.destination(msg);
+               return addr == call AMPacket.address() || addr == AM_BROADCAST_ADDR;
+       }
+
+       inline command am_id_t AMPacket.type(message_t* msg)
+       {
+               return call IEEE154PacketLayer.getType(msg);
+       }
+
+       inline command void AMPacket.setType(message_t* msg, am_id_t type)
+       {
+               call IEEE154PacketLayer.setType(msg, type);
+       }
+  
+       inline command am_group_t AMPacket.group(message_t* msg) 
+       {
+               return call IEEE154PacketLayer.getDestPan(msg);
+       }
+
+       inline command void AMPacket.setGroup(message_t* msg, am_group_t grp)
+       {
+               call IEEE154PacketLayer.setDestPan(msg, grp);
+       }
+}
diff --git a/tos/chips/rf2xx/layers/LowPowerListeningDummyC.nc b/tos/chips/rf2xx/layers/LowPowerListeningDummyC.nc
new file mode 100644 (file)
index 0000000..fab0314
--- /dev/null
@@ -0,0 +1,50 @@
+/*
+ * Copyright (c) 2009, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
+ * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ * 
+ * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
+ * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+ *
+ * Author: Miklos Maroti
+ */
+
+configuration LowPowerListeningDummyC
+{
+       provides
+       {
+               interface SplitControl;
+               interface Send;
+               interface Receive;
+
+               interface LowPowerListening;
+       }
+       uses
+       {
+               interface SplitControl as SubControl;
+               interface Send as SubSend;
+               interface Receive as SubReceive;
+       }
+}
+
+implementation
+{
+       SplitControl = SubControl;
+       Send = SubSend;
+       Receive = SubReceive;
+
+       components LowPowerListeningDummyP;
+       LowPowerListening = LowPowerListeningDummyP;
+}
diff --git a/tos/chips/rf2xx/layers/LowPowerListeningDummyP.nc b/tos/chips/rf2xx/layers/LowPowerListeningDummyP.nc
new file mode 100644 (file)
index 0000000..953fc28
--- /dev/null
@@ -0,0 +1,50 @@
+/*
+ * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
+ * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ * 
+ * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
+ * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+ *
+ * Author: Miklos Maroti
+ */
+
+module LowPowerListeningDummyP
+{
+       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/rf2xx/layers/LowPowerListeningLayer.h b/tos/chips/rf2xx/layers/LowPowerListeningLayer.h
new file mode 100644 (file)
index 0000000..51ee4dd
--- /dev/null
@@ -0,0 +1,32 @@
+/*
+ * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
+ * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ * 
+ * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
+ * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+ *
+ * Author: Miklos Maroti
+ */
+
+#ifndef __LOWPOWERLISTENINGLAYER_H__
+#define __LOWPOWERLISTENINGLAYER_H__
+
+typedef struct lpl_metadata_t
+{
+       uint16_t sleepint;
+} lpl_metadata_t;
+
+#endif//__LOWPOWERLISTENINGLAYER_H__
index 5cc93f00512aa088b276010886de7feaeb576090..0c6898bfbf2e5cafae0f187685fcdd133a0a666b 100644 (file)
@@ -21,6 +21,8 @@
  * Author: Miklos Maroti
  */
 
+#include <LowPowerListeningLayer.h>
+
 #warning "*** USING LOW POWER LISTENING LAYER"
 
 configuration LowPowerListeningLayerC
@@ -39,8 +41,8 @@ configuration LowPowerListeningLayerC
                interface Send as SubSend;
                interface Receive as SubReceive;
 
-               interface PacketField<uint16_t> as PacketSleepInterval;
-               interface IEEE154Packet2;
+               interface PacketData<lpl_metadata_t> as PacketLplMetadata;
+               interface IEEE154PacketLayer;
                interface PacketAcknowledgements;
        }
 }
@@ -57,8 +59,8 @@ implementation
        SubControl = LowPowerListeningLayerP;
        SubSend = LowPowerListeningLayerP;
        SubReceive = LowPowerListeningLayerP;
-       PacketSleepInterval = LowPowerListeningLayerP;
-       IEEE154Packet2 = LowPowerListeningLayerP;
+       PacketLplMetadata = LowPowerListeningLayerP;
+       IEEE154PacketLayer = LowPowerListeningLayerP;
        PacketAcknowledgements = LowPowerListeningLayerP;
        
        LowPowerListeningLayerP.Timer -> TimerMilliC;
index fc02621b69af7b9cf6bbfa28a2591427af0ca9f0..226192232fa5f038134c851594c1edf7889994b9 100644 (file)
@@ -22,6 +22,7 @@
  */
 
 #include <RadioAssert.h>
+#include <LowPowerListeningLayer.h>
 
 module LowPowerListeningLayerP
 {
@@ -40,8 +41,8 @@ module LowPowerListeningLayerP
                interface Send as SubSend;
                interface Receive as SubReceive;
 
-               interface PacketField<uint16_t> as PacketSleepInterval;
-               interface IEEE154Packet2;
+               interface PacketData<lpl_metadata_t> as PacketLplMetadata;
+               interface IEEE154PacketLayer;
                interface PacketAcknowledgements;
                interface Timer<TMilli>;
        }
@@ -77,22 +78,22 @@ implementation
        {
                OFF = 0,                                        
                OFF_SUBSTOP = 1,                        // must have consecutive indices
-               OFF_SUBSTOP_DONE = 2,           // must have consecutive indices
+               OFF_SUBSTOP_DONE = 2,                   // must have consecutive indices
                OFF_STOP_END = 3,                       // must have consecutive indices
                OFF_START_END = 4,
 
-               LISTEN_SUBSTART = 5,            // must have consecutive indices
-               LISTEN_SUBSTART_DONE = 6,       // must have consecutive indices
+               LISTEN_SUBSTART = 5,                    // must have consecutive indices
+               LISTEN_SUBSTART_DONE = 6,               // must have consecutive indices
                LISTEN_TIMER = 7,                       // must have consecutive indices
-               LISTEN = 8,                                     // must have consecutive indices
+               LISTEN = 8,                             // must have consecutive indices
 
                SLEEP_SUBSTOP = 9,                      // must have consecutive indices
-               SLEEP_SUBSTOP_DONE = 10,        // must have consecutive indices
+               SLEEP_SUBSTOP_DONE = 10,                // must have consecutive indices
                SLEEP_TIMER = 11,                       // must have consecutive indices
-               SLEEP = 12,                                     // must have consecutive indices
+               SLEEP = 12,                             // must have consecutive indices
 
                SEND_SUBSTART = 13,                     // must have consecutive indices
-               SEND_SUBSTART_DONE = 14,        // must have consecutive indices
+               SEND_SUBSTART_DONE = 14,                // must have consecutive indices
                SEND_TIMER = 15,                        // must have consecutive indices
                SEND_SUBSEND= 16,
                SEND_SUBSEND_DONE = 17,
@@ -335,7 +336,7 @@ implementation
                if( error != SUCCESS
                        || call LowPowerListening.getRxSleepInterval(msg) == 0
                        || state == SEND_SUBSEND_DONE_LAST
-                       || (call IEEE154Packet2.getAckRequired(msg) && call PacketAcknowledgements.wasAcked(msg)) )
+                       || (call IEEE154PacketLayer.getAckRequired(msg) && call PacketAcknowledgements.wasAcked(msg)) )
                {
                        call Timer.stop();
                        state = SEND_DONE;
@@ -379,7 +380,7 @@ implementation
        }
 
        command void LowPowerListening.setLocalSleepInterval(uint16_t interval)
-    {
+       {
                if( interval < MIN_SLEEP )
                        interval = 0;
                else if( interval > MAX_SLEEP )
@@ -396,7 +397,7 @@ implementation
        }
 
        command uint16_t LowPowerListening.getLocalSleepInterval()
-    {  
+       {       
                return sleepInterval;
        }
 
@@ -418,26 +419,30 @@ implementation
                else if( interval > MAX_SLEEP )
                        interval = MAX_SLEEP;
 
-               call PacketSleepInterval.set(msg, interval);
+               (call PacketLplMetadata.get(msg))->sleepint = interval;
        }
 
        command uint16_t LowPowerListening.getRxSleepInterval(message_t *msg)
-    {
-               if( ! call PacketSleepInterval.isSet(msg) )
-                       return sleepInterval;
+       {
+               uint16_t sleepint = (call PacketLplMetadata.get(msg))->sleepint;
 
-               return call PacketSleepInterval.get(msg);
+               return sleepint != 0 ? sleepint : sleepInterval;
        }
 
        command void LowPowerListening.setRxDutyCycle(message_t *msg, uint16_t dutyCycle)
-    {
+       {
                call LowPowerListening.setRxSleepInterval(msg, 
                        call LowPowerListening.dutyCycleToSleepInterval(dutyCycle));
        }
 
        command uint16_t LowPowerListening.getRxDutyCycle(message_t *msg)
-    {
+       {
                return call LowPowerListening.sleepIntervalToDutyCycle(
                        call LowPowerListening.getRxSleepInterval(msg));
        }
+
+       async event void PacketLplMetadata.clear(message_t* msg)
+       {
+               (call PacketLplMetadata.get(msg))->sleepint = 0;
+       }
 }
diff --git a/tos/chips/rf2xx/layers/MetadataFlagsLayer.h b/tos/chips/rf2xx/layers/MetadataFlagsLayer.h
new file mode 100644 (file)
index 0000000..5694d07
--- /dev/null
@@ -0,0 +1,33 @@
+/*
+ * Copyright (c) 2009, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
+ * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ * 
+ * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
+ * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+ *
+ * Author: Miklos Maroti
+ */
+
+#ifndef __METADATAFLAGSLAYER_H__
+#define __METADATAFLAGSLAYER_H__
+
+typedef struct flags_metadata_t
+{
+       // TODO: make sure that we have no more than 8 flags
+       uint8_t flags;
+} flags_metadata_t;
+
+#endif//__METADATAFLAGSLAYER_H__
diff --git a/tos/chips/rf2xx/layers/MetadataFlagsLayerC.nc b/tos/chips/rf2xx/layers/MetadataFlagsLayerC.nc
new file mode 100644 (file)
index 0000000..dffafb0
--- /dev/null
@@ -0,0 +1,73 @@
+/*
+ * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
+ * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ * 
+ * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
+ * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+ *
+ * Author: Miklos Maroti
+ */
+
+#include <MetadataFlagsLayer.h>
+#include <RadioAssert.h>
+
+module MetadataFlagsLayerC
+{
+       provides 
+       {
+               interface PacketFlag[uint8_t bit];
+       }
+
+       uses
+       {
+               interface PacketData<flags_metadata_t> as PacketFlagsMetadata;
+       }
+}
+
+implementation
+{
+       async command bool PacketFlag.get[uint8_t bit](message_t* msg)
+       {
+               return (call PacketFlagsMetadata.get(msg))->flags & (1<<bit);
+       }
+
+       async command void PacketFlag.set[uint8_t bit](message_t* msg)
+       {
+               ASSERT( bit  < 8 );
+
+               (call PacketFlagsMetadata.get(msg))->flags |= (1<<bit);
+       }
+
+       async command void PacketFlag.clear[uint8_t bit](message_t* msg)
+       {
+               ASSERT( bit  < 8 );
+
+               (call PacketFlagsMetadata.get(msg))->flags &= ~(1<<bit);
+       }
+
+       async command void PacketFlag.setValue[uint8_t bit](message_t* msg, bool value)
+       {
+               if( value )
+                       call PacketFlag.set[bit](msg);
+               else
+                       call PacketFlag.clear[bit](msg);
+       }
+
+       async event void PacketFlagsMetadata.clear(message_t* msg)
+       {
+               (call PacketFlagsMetadata.get(msg))->flags = 0;
+       }
+}
index 785e61ec1dd94871c8128b27db8080bfe3002bfb..df518ce189f335e9460efb2b04d3674b40027fed 100644 (file)
 #ifndef __PACKETLINKLAYER_H__
 #define __PACKETLINKLAYER_H__
 
-typedef struct packet_link_metadata_t
+typedef struct link_metadata_t
 {
-       nx_uint16_t maxRetries;
-       nx_uint16_t retryDelay;
-} packet_link_metadata_t;
+       uint16_t maxRetries;
+       uint16_t retryDelay;
+} link_metadata_t;
 
 #endif//__PACKETLINKLAYER_H__
index 34ea89118e613ff45a25d8c4767d4a51d0d8115c..5701af73a1132bcf6d3180ce49e424d6969c851c 100644 (file)
@@ -69,21 +69,19 @@ configuration PacketLinkLayerC {
   
   uses {
     interface Send as SubSend;
-    interface PacketData<packet_link_metadata_t>;
+    interface PacketData<link_metadata_t> as PacketLinkMetadata;
     interface PacketAcknowledgements;
   }
 }
 
 implementation {
-  components PacketLinkLayerP,
-      RF230PacketC,
-      new TimerMilliC() as DelayTimerC;
+  components PacketLinkLayerP, new TimerMilliC() as DelayTimerC;
   
   PacketLink = PacketLinkLayerP;
   Send = PacketLinkLayerP.Send;
   SubSend = PacketLinkLayerP.SubSend;
   PacketAcknowledgements = PacketLinkLayerP;
-  PacketData = PacketLinkLayerP;
-  
+  PacketLinkMetadata = PacketLinkLayerP;
+
   PacketLinkLayerP.DelayTimer -> DelayTimerC;
 }
index a54e135fa09d247b9a68715c5d12bc2e6f6657fc..9418770d33d7799f0ed53b6f23296aadf59daf08 100644 (file)
@@ -69,7 +69,7 @@ module PacketLinkLayerP {
     interface Send as SubSend;
     interface PacketAcknowledgements;
     interface Timer<TMilli> as DelayTimer;
-    interface PacketData<packet_link_metadata_t>;
+    interface PacketData<link_metadata_t> as PacketLinkMetadata;
   }
 }
 
@@ -99,7 +99,7 @@ implementation {
    *     the message
    */
   command void PacketLink.setRetries(message_t *msg, uint16_t maxRetries) {
-    (call PacketData.getData(msg))->maxRetries = maxRetries;
+    (call PacketLinkMetadata.get(msg))->maxRetries = maxRetries;
   }
 
   /**
@@ -108,21 +108,21 @@ implementation {
    * @param retryDelay the delay betweeen retry attempts, in milliseconds
    */
   command void PacketLink.setRetryDelay(message_t *msg, uint16_t retryDelay) {
-    (call PacketData.getData(msg))->retryDelay = retryDelay;
+    (call PacketLinkMetadata.get(msg))->retryDelay = retryDelay;
   }
 
   /**
    * @return the maximum number of retry attempts for this message
    */
   command uint16_t PacketLink.getRetries(message_t *msg) {
-    return (call PacketData.getData(msg))->maxRetries;
+    return (call PacketLinkMetadata.get(msg))->maxRetries;
   }
 
   /**
    * @return the delay between retry attempts in ms for this message
    */
   command uint16_t PacketLink.getRetryDelay(message_t *msg) {
-    return (call PacketData.getData(msg))->retryDelay;
+    return (call PacketLinkMetadata.get(msg))->retryDelay;
   }
 
   /**
@@ -132,8 +132,8 @@ implementation {
     return call PacketAcknowledgements.wasAcked(msg);
   }
 
-  async event void PacketData.clear(packet_link_metadata_t* data) {
-    data->maxRetries = 0;
+  async event void PacketLinkMetadata.clear(message_t* msg) {
+    (call PacketLinkMetadata.get(msg))->maxRetries = 0;
   }
 
   /***************** Send Commands ***************/
index b3c87c735b00e9f4448040de6e3e52d5dc2de5a9..5f7b8a3fc1354e98f419658a5c495ed1261a7d34 100755 (executable)
@@ -31,17 +31,18 @@ interface SoftwareAckConfig
         */
        async command uint16_t getAckTimeout();
 
+       /**
+        * Sets the flag in the message indicating to the receiver whether
+        * the message should be acknowledged.
+        */
+       async command void setAckRequired(message_t* msg, bool ack);
+        
        /**
         * Returns TRUE if the layer should wait for a software acknowledgement
         * to be received after this packet was transmitted.
         */
        async command bool requiresAckWait(message_t* msg);
 
-       /**
-        * Sets for the transmitted message whether it was acknowledged or not.
-        */
-       async command void setAckReceived(message_t* msg, bool acked);
-
        /**
         * Returns TRUE if the received packet is an acknowledgement packet.
         * The AckedSend layer will filter out all received acknowledgement
index 97703e1f90ba6c1d301e76744887c5bda544cb09..44e2cf063a2705f83db05b9d54375fd278d3ba51 100755 (executable)
@@ -27,6 +27,7 @@ configuration SoftwareAckLayerC
        {
                interface RadioSend;
                interface RadioReceive;
+               interface PacketAcknowledgements;
        }
        uses
        {
@@ -39,13 +40,15 @@ configuration SoftwareAckLayerC
 
 implementation
 {
-       components SoftwareAckLayerP, RadioAlarmC;
+       components SoftwareAckLayerP, RadioAlarmC, new MetadataFlagC();
 
        RadioSend = SoftwareAckLayerP;
        RadioReceive = SoftwareAckLayerP;
        SubSend = SoftwareAckLayerP;
        SubReceive = SoftwareAckLayerP;
        Config = SoftwareAckLayerP;
+       PacketAcknowledgements = SoftwareAckLayerP;
 
        SoftwareAckLayerP.RadioAlarm -> RadioAlarmC.RadioAlarm[unique("RadioAlarm")];
+       SoftwareAckLayerP.AckReceivedFlag -> MetadataFlagC;
 }
index 02ca70de1f69845a02b5ce62590184465c29a8ad..643248177a33f00140660db08c98fef362aee096 100644 (file)
@@ -30,6 +30,7 @@ module SoftwareAckLayerP
        {
                interface RadioSend;
                interface RadioReceive;
+               interface PacketAcknowledgements;
        }
        uses
        {
@@ -38,6 +39,7 @@ module SoftwareAckLayerP
                interface RadioAlarm;
 
                interface SoftwareAckConfig;
+               interface PacketFlag as AckReceivedFlag;
        }
 }
 
@@ -69,7 +71,7 @@ implementation
                {
                        if( (error = call SubSend.send(msg)) == SUCCESS )
                        {
-                               call SoftwareAckConfig.setAckReceived(msg, FALSE);
+                               call AckReceivedFlag.clear(msg);
                                state = STATE_DATA_SEND;
                                txMsg = msg;
                        }
@@ -136,7 +138,7 @@ implementation
                        ASSERT( !ack || call SoftwareAckConfig.verifyAckPacket(txMsg, msg) );
 
                        call RadioAlarm.cancel();
-                       call SoftwareAckConfig.setAckReceived(txMsg, ack);
+                       call AckReceivedFlag.setValue(txMsg, ack);
 
                        state = STATE_READY;
                        signal RadioSend.sendDone(SUCCESS);
@@ -158,4 +160,27 @@ implementation
 
                return signal RadioReceive.receive(msg);
        }
+
+/*----------------- PacketAcknowledgements -----------------*/
+
+       async command error_t PacketAcknowledgements.requestAck(message_t* msg)
+       {
+               call SoftwareAckConfig.setAckRequired(msg, TRUE);
+
+               return SUCCESS;
+       }
+
+       async command error_t PacketAcknowledgements.noAck(message_t* msg)
+       {
+               call SoftwareAckConfig.setAckRequired(msg, FALSE);
+
+               return SUCCESS;
+       }
+
+       async command bool PacketAcknowledgements.wasAcked(message_t* msg)
+       {
+               return call AckReceivedFlag.get(msg);
+       }
+
+
 }
diff --git a/tos/chips/rf2xx/layers/TimeStampingLayer.h b/tos/chips/rf2xx/layers/TimeStampingLayer.h
new file mode 100644 (file)
index 0000000..dc0a43c
--- /dev/null
@@ -0,0 +1,32 @@
+/*
+ * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
+ * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ * 
+ * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
+ * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+ *
+ * Author: Miklos Maroti
+ */
+
+#ifndef __TIMESTAMPINGLAYER_H__
+#define __TIMESTAMPINGLAYER_H__
+
+typedef struct timestamp_metadata_t
+{
+       uint32_t timestamp;
+} timestamp_metadata_t;
+
+#endif//__TIMESTAMPINGLAYER_H__
diff --git a/tos/chips/rf2xx/layers/TimeStampingLayerC.nc b/tos/chips/rf2xx/layers/TimeStampingLayerC.nc
new file mode 100644 (file)
index 0000000..a8aadea
--- /dev/null
@@ -0,0 +1,52 @@
+/*
+ * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
+ * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ * 
+ * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
+ * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+ *
+ * Author: Miklos Maroti
+ */
+
+configuration TimeStampingLayerC
+{
+       provides
+       {
+               interface PacketTimeStamp<TMilli, uint32_t> as PacketTimeStampMilli;
+               interface PacketTimeStamp<TRadio, uint32_t> as PacketTimeStampRadio;
+       }
+
+       uses
+       {
+               interface LocalTime<TRadio> as LocalTimeRadio;
+               interface PacketData<timestamp_metadata_t> as PacketTimeStampMetadata;
+       }
+}
+
+implementation
+{
+       components TimeStampingLayerP, LocalTimeMilliC;
+
+       PacketTimeStampMilli = TimeStampingLayerP;
+       PacketTimeStampRadio = TimeStampingLayerP;
+       PacketTimeStampMetadata = TimeStampingLayerP.PacketTimeStampMetadata;
+
+       LocalTimeRadio = TimeStampingLayerP;
+       TimeStampingLayerP.LocalTimeMilli -> LocalTimeMilliC;
+
+       components new MetadataFlagC() as TimeStampFlagC;
+       TimeStampingLayerP.TimeStampFlag -> TimeStampFlagC;
+}
diff --git a/tos/chips/rf2xx/layers/TimeStampingLayerP.nc b/tos/chips/rf2xx/layers/TimeStampingLayerP.nc
new file mode 100644 (file)
index 0000000..33b14b8
--- /dev/null
@@ -0,0 +1,96 @@
+/*
+ * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
+ * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
+ * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+ *
+ * Author: Miklos Maroti
+ */
+
+#include <RadioConfig.h>
+#include <TimeStampingLayer.h>
+
+module TimeStampingLayerP
+{
+       provides
+       {
+               interface PacketTimeStamp<TMilli, uint32_t> as PacketTimeStampMilli;
+               interface PacketTimeStamp<TRadio, uint32_t> as PacketTimeStampRadio;
+       }
+
+       uses
+       {
+               interface PacketFlag as TimeStampFlag;
+
+               interface LocalTime<TRadio> as LocalTimeRadio;
+               interface LocalTime<TMilli> as LocalTimeMilli;
+
+               interface PacketData<timestamp_metadata_t> as PacketTimeStampMetadata;
+       }
+}
+
+implementation
+{
+       async command bool PacketTimeStampRadio.isValid(message_t* msg)
+       {
+               return call TimeStampFlag.get(msg);
+       }
+
+       async command uint32_t PacketTimeStampRadio.timestamp(message_t* msg)
+       {
+               return (call PacketTimeStampMetadata.get(msg))->timestamp;
+       }
+
+       async command void PacketTimeStampRadio.clear(message_t* msg)
+       {
+               call TimeStampFlag.clear(msg);
+       }
+
+       async command void PacketTimeStampRadio.set(message_t* msg, uint32_t value)
+       {
+               call TimeStampFlag.set(msg);
+               (call PacketTimeStampMetadata.get(msg))->timestamp = value;
+       }
+
+       async event void PacketTimeStampMetadata.clear(message_t* msg)
+       {
+       }
+
+       async command bool PacketTimeStampMilli.isValid(message_t* msg)
+       {
+               return call PacketTimeStampRadio.isValid(msg);
+       }
+
+       async command uint32_t PacketTimeStampMilli.timestamp(message_t* msg)
+       {
+               int32_t offset = call PacketTimeStampRadio.timestamp(msg) - call LocalTimeRadio.get();
+
+               return (offset >> RADIO_ALARM_MILLI_EXP) + call LocalTimeMilli.get();
+       }
+
+       async command void PacketTimeStampMilli.clear(message_t* msg)
+       {
+               call PacketTimeStampRadio.clear(msg);
+       }
+
+       async command void PacketTimeStampMilli.set(message_t* msg, uint32_t value)
+       {
+               int32_t offset = (value - call LocalTimeMilli.get()) << RADIO_ALARM_MILLI_EXP;
+
+               call PacketTimeStampRadio.set(msg, offset + call LocalTimeRadio.get());
+       }
+}
diff --git a/tos/chips/rf2xx/rf212/RF212.h b/tos/chips/rf2xx/rf212/RF212.h
deleted file mode 100644 (file)
index 7afb78f..0000000
+++ /dev/null
@@ -1,162 +0,0 @@
-/*
- * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
- * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
- * 
- * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
- * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
- *
- * Author: Miklos Maroti
- */
-
-#ifndef __RF212_H__
-#define __RF212_H__
-
-enum rf212_registers_enum
-{
-       RF212_TRX_STATUS = 0x01,
-       RF212_TRX_STATE = 0x02,
-       RF212_TRX_CTRL_0 = 0x03,
-       RF212_TRX_CTRL_1 = 0x04,
-       RF212_PHY_TX_PWR = 0x05,
-       RF212_PHY_RSSI = 0x06,
-       RF212_PHY_ED_LEVEL = 0x07,
-       RF212_PHY_CC_CCA = 0x08,
-       RF212_CCA_THRES = 0x09,
-       RF212_IRQ_MASK = 0x0E,
-       RF212_IRQ_STATUS = 0x0F,
-       RF212_VREG_CTRL = 0x10,
-       RF212_BATMON = 0x11,
-       RF212_XOSC_CTRL = 0x12,
-       RF212_PLL_CF = 0x1A,
-       RF212_PLL_DCU = 0x1B,
-       RF212_PART_NUM = 0x1C,
-       RF212_VERSION_NUM = 0x1D,
-       RF212_MAN_ID_0 = 0x1E,
-       RF212_MAN_ID_1 = 0x1F,
-       RF212_SHORT_ADDR_0 = 0x20,
-       RF212_SHORT_ADDR_1 = 0x21,
-       RF212_PAN_ID_0 = 0x22,
-       RF212_PAN_ID_1 = 0x23,
-       RF212_IEEE_ADDR_0 = 0x24,
-       RF212_IEEE_ADDR_1 = 0x25,
-       RF212_IEEE_ADDR_2 = 0x26,
-       RF212_IEEE_ADDR_3 = 0x27,
-       RF212_IEEE_ADDR_4 = 0x28,
-       RF212_IEEE_ADDR_5 = 0x29,
-       RF212_IEEE_ADDR_6 = 0x2A,
-       RF212_IEEE_ADDR_7 = 0x2B,
-       RF212_XAH_CTRL = 0x2C,
-       RF212_CSMA_SEED_0 = 0x2D,
-       RF212_CSMA_SEED_1 = 0x2E,
-};
-
-enum rf212_trx_status_enums
-{
-       RF212_CCA_DONE = 1 << 7,
-       RF212_CCA_STATUS = 1 << 6,
-       RF212_TRX_STATUS_MASK = 0x1F,
-       RF212_P_ON = 0,
-       RF212_BUSY_RX = 1,
-       RF212_BUSY_TX = 2,
-       RF212_RX_ON = 6,
-       RF212_TRX_OFF = 8,
-       RF212_PLL_ON = 9,
-       RF212_SLEEP = 15,
-       RF212_BUSY_RX_AACK = 16,
-       RF212_BUSR_TX_ARET = 17,
-       RF212_RX_AACK_ON = 22,
-       RF212_TX_ARET_ON = 25,
-       RF212_RX_ON_NOCLK = 28,
-       RF212_AACK_ON_NOCLK = 29,
-       RF212_BUSY_RX_AACK_NOCLK = 30,
-       RF212_STATE_TRANSITION_IN_PROGRESS = 31,
-};
-
-enum rf212_trx_state_enums
-{
-       RF212_TRAC_STATUS_MASK = 0xE0,
-       RF212_TRAC_SUCCESS = 0,
-       RF212_TRAC_CHANNEL_ACCESS_FAILURE = 3 << 5,
-       RF212_TRAC_NO_ACK = 5 << 5,
-       RF212_TRX_CMD_MASK = 0x1F,
-       RF212_NOP = 0,
-       RF212_TX_START = 2,
-       RF212_FORCE_TRX_OFF = 3,
-};
-
-enum rf212_phy_rssi_enums
-{
-       RF212_RX_CRC_VALID = 1 << 7,
-       RF212_RSSI_MASK = 0x1F,
-};
-
-enum rf212_phy_cc_cca_enums
-{
-       RF212_CCA_REQUEST = 1 << 7,
-       RF212_CCA_MODE_0 = 0 << 5,
-       RF212_CCA_MODE_1 = 1 << 5,
-       RF212_CCA_MODE_2 = 2 << 5,
-       RF212_CCA_MODE_3 = 3 << 5,
-       RF212_CHANNEL_DEFAULT = 11,
-       RF212_CHANNEL_MASK = 0x1F,
-};
-
-enum rf212_irq_register_enums
-{
-       RF212_IRQ_BAT_LOW = 1 << 7,
-       RF212_IRQ_TRX_UR = 1 << 6,
-       RF212_IRQ_AMI = 1 << 5,
-       RF212_IRQ_CCA_ED_DONE = 1 << 4,
-       RF212_IRQ_TRX_END = 1 << 3,
-       RF212_IRQ_RX_START = 1 << 2,
-       RF212_IRQ_PLL_UNLOCK = 1 << 1,
-       RF212_IRQ_PLL_LOCK = 1 << 0,
-};
-
-enum rf212_batmon_enums
-{
-       RF212_BATMON_OK = 1 << 5,
-       RF212_BATMON_VHR = 1 << 4,
-       RF212_BATMON_VTH_MASK = 0x0F,
-};
-
-enum rf212_vreg_ctrl_enums
-{
-       RF212_AVREG_EXT = 1 << 7,
-       RF212_AVDD_OK = 1 << 6,
-       RF212_DVREG_EXT = 1 << 3,
-       RF212_DVDD_OK = 1 << 2,
-};
-
-enum rf212_xosc_ctrl_enums
-{
-       RF212_XTAL_MODE_OFF = 0 << 4,
-       RF212_XTAL_MODE_EXTERNAL = 4 << 4,
-       RF212_XTAL_MODE_INTERNAL = 15 << 4,
-};
-
-enum rf212_spi_command_enums
-{
-       RF212_CMD_REGISTER_READ = 0x80,
-       RF212_CMD_REGISTER_WRITE = 0xC0,
-       RF212_CMD_REGISTER_MASK = 0x3F,
-       RF212_CMD_FRAME_READ = 0x20,
-       RF212_CMD_FRAME_WRITE = 0x60,
-       RF212_CMD_SRAM_READ = 0x00,
-       RF212_CMD_SRAM_WRITE = 0x40,
-};
-
-#endif//__RF212_H__
diff --git a/tos/chips/rf2xx/rf212/RF212ActiveMessage.h b/tos/chips/rf2xx/rf212/RF212ActiveMessage.h
new file mode 100644 (file)
index 0000000..e13bba9
--- /dev/null
@@ -0,0 +1,54 @@
+/*
+ * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
+ * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ * 
+ * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
+ * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+ *
+ * Author: Miklos Maroti
+ */
+
+#ifndef __RF212ACTIVEMESSAGE_H__
+#define __RF212ACTIVEMESSAGE_H__
+
+#include <IEEE154PacketLayer.h>
+#include <MetadataFlagsLayer.h>
+#include <RF212DriverLayer.h>
+#include <TimeStampingLayer.h>
+#include <LowPowerListeningLayer.h>
+#include <PacketLinkLayer.h>
+
+typedef ieee154_header_t rf212packet_header_t;
+
+typedef nx_struct rf212packet_footer_t
+{
+       // the time stamp is not recorded here, time stamped messaged cannot have max length
+} rf212packet_footer_t;
+
+typedef struct rf212packet_metadata_t
+{
+       flags_metadata_t flags;
+       rf212_metadata_t rf212;
+       timestamp_metadata_t timestamp;
+#ifdef LOW_POWER_LISTENING
+       lpl_metadata_t lpl;
+#endif
+#ifdef PACKET_LINK
+       link_metadata_t link;
+#endif
+} rf212packet_metadata_t;
+
+#endif//__RF212ACTIVEMESSAGE_H__
index 65eba63c45f23477b4dd47fbb9d63f0c61ffc58d..bd5fe3c01372fc4e7c7c35388a727326d7f18c90 100644 (file)
@@ -36,8 +36,6 @@ configuration RF212ActiveMessageC
                interface Packet;
                interface AMPacket;
                interface PacketAcknowledgements;
-
-               // we provide a dummy LowPowerListening interface if LOW_POWER_LISTENING is not defined
                interface LowPowerListening;
 
 #ifdef PACKET_LINK
@@ -50,6 +48,7 @@ configuration RF212ActiveMessageC
                interface PacketField<uint8_t> as PacketTransmitPower;
                interface PacketField<uint8_t> as PacketRSSI;
 
+               interface LocalTime<TRadio> as LocalTimeRadio;
                interface PacketTimeStamp<TRadio, uint32_t> as PacketTimeStampRadio;
                interface PacketTimeStamp<TMilli, uint32_t> as PacketTimeStampMilli;
        }
@@ -57,112 +56,142 @@ configuration RF212ActiveMessageC
 
 implementation
 {
-       components RF212ActiveMessageP, RF212PacketC, IEEE154Packet2C, RadioAlarmC;
+       components RF212ActiveMessageP, IEEE154PacketLayerC, RadioAlarmC;
 
 #ifdef RADIO_DEBUG
        components AssertC;
 #endif
 
-       RF212ActiveMessageP.IEEE154Packet2 -> IEEE154Packet2C;
-       RF212ActiveMessageP.Packet -> RF212PacketC;
+       RF212ActiveMessageP.IEEE154PacketLayer -> IEEE154PacketLayerC;
        RF212ActiveMessageP.RadioAlarm -> RadioAlarmC.RadioAlarm[unique("RadioAlarm")];
+       RF212ActiveMessageP.PacketTimeStamp -> TimeStampingLayerC;
 
-       Packet = RF212PacketC;
-       AMPacket = RF212PacketC;
-       PacketAcknowledgements = RF212PacketC;
-       PacketLinkQuality = RF212PacketC.PacketLinkQuality;
-       PacketTransmitPower = RF212PacketC.PacketTransmitPower;
-       PacketRSSI = RF212PacketC.PacketRSSI;
-       PacketTimeStampRadio = RF212PacketC;
-       PacketTimeStampMilli = RF212PacketC;
-       LowPowerListening = LowPowerListeningLayerC;
-       RadioChannel = MessageBufferLayerC;
+       Packet = RF212ActiveMessageP;
+
+// -------- ActiveMessage
 
        components ActiveMessageLayerC;
+       ActiveMessageLayerC.Config -> RF212ActiveMessageP;
+       ActiveMessageLayerC.AMPacket -> IEEE154PacketLayerC;
+       ActiveMessageLayerC.SubSend -> IEEE154NetworkLayerC;
+       ActiveMessageLayerC.SubReceive -> IEEE154NetworkLayerC;
+       AMSend = ActiveMessageLayerC;
+       Receive = ActiveMessageLayerC.Receive;
+       Snoop = ActiveMessageLayerC.Snoop;
+       AMPacket = IEEE154PacketLayerC;
+
+// -------- IEEE154Network
+
 #ifdef TFRAMES_ENABLED
        components new DummyLayerC() as IEEE154NetworkLayerC;
 #else
        components IEEE154NetworkLayerC;
 #endif
+       IEEE154NetworkLayerC.SubSend -> UniqueLayerC;
+       IEEE154NetworkLayerC.SubReceive -> LowPowerListeningLayerC;
+
+// -------- UniqueLayer Send part (wired twice)
+
+       components UniqueLayerC;
+       UniqueLayerC.Config -> RF212ActiveMessageP;
+       UniqueLayerC.SubSend -> LowPowerListeningLayerC;
+
+// -------- Low Power Listening 
 
 #ifdef LOW_POWER_LISTENING
        components LowPowerListeningLayerC;
-       LowPowerListeningLayerC.PacketSleepInterval -> RF230PacketC;
-       LowPowerListeningLayerC.IEEE154Packet2 -> IEEE154Packet2C;
-       LowPowerListeningLayerC.PacketAcknowledgements -> RF230PacketC;
+       LowPowerListeningLayerC.PacketLplMetadata -> RF212ActiveMessageP;
+       LowPowerListeningLayerC.IEEE154PacketLayer -> IEEE154PacketLayerC;
+       LowPowerListeningLayerC.PacketAcknowledgements -> SoftwareAckLayerC;
 #else  
-       components new DummyLayerC() as LowPowerListeningLayerC;
+       components LowPowerListeningDummyC as LowPowerListeningLayerC;
 #endif
+       LowPowerListeningLayerC.SubControl -> MessageBufferLayerC;
+       LowPowerListeningLayerC.SubSend -> PacketLinkLayerC;
+       LowPowerListeningLayerC.SubReceive -> MessageBufferLayerC;
+       SplitControl = LowPowerListeningLayerC;
+       LowPowerListening = LowPowerListeningLayerC;
+
+// -------- Packet Link
 
 #ifdef PACKET_LINK
        components PacketLinkLayerC;
        PacketLink = PacketLinkLayerC;
-       PacketLinkLayerC.PacketData -> RF230PacketC;
-       PacketLinkLayerC.PacketAcknowledgements -> RF230PacketC;
+       PacketLinkLayerC.PacketLinkMetadata -> RF212ActiveMessageP;
+       PacketLinkLayerC.PacketAcknowledgements -> SoftwareAckLayerC;
 #else
        components new DummyLayerC() as PacketLinkLayerC;
 #endif
-
-       components MessageBufferLayerC;
-       components UniqueLayerC;
-       components TrafficMonitorLayerC;
-
-#ifdef SLOTTED_MAC
-       components SlottedCollisionLayerC as CollisionAvoidanceLayerC;
-#else
-       components RandomCollisionLayerC as CollisionAvoidanceLayerC;
-#endif
-
-       components SoftwareAckLayerC;
-       components new DummyLayerC() as CsmaLayerC;
-       components RF212DriverLayerC;
-
-       SplitControl = LowPowerListeningLayerC;
-       AMSend = ActiveMessageLayerC;
-       Receive = ActiveMessageLayerC.Receive;
-       Snoop = ActiveMessageLayerC.Snoop;
-
-       ActiveMessageLayerC.Config -> RF212ActiveMessageP;
-       ActiveMessageLayerC.AMPacket -> IEEE154Packet2C;
-       ActiveMessageLayerC.SubSend -> IEEE154NetworkLayerC;
-       ActiveMessageLayerC.SubReceive -> IEEE154NetworkLayerC;
-
-       IEEE154NetworkLayerC.SubSend -> UniqueLayerC;
-       IEEE154NetworkLayerC.SubReceive -> LowPowerListeningLayerC;
-
-       // the UniqueLayer is wired at two points
-       UniqueLayerC.Config -> RF212ActiveMessageP;
-       UniqueLayerC.SubSend -> LowPowerListeningLayerC;
-
-       LowPowerListeningLayerC.SubControl -> MessageBufferLayerC;
-       LowPowerListeningLayerC.SubSend -> PacketLinkLayerC;
-       LowPowerListeningLayerC.SubReceive -> MessageBufferLayerC;
-
        PacketLinkLayerC.SubSend -> MessageBufferLayerC;
 
-       MessageBufferLayerC.Packet -> RF212PacketC;
+// -------- MessageBuffer
+
+       components MessageBufferLayerC;
+       MessageBufferLayerC.Packet -> RF212ActiveMessageP;
        MessageBufferLayerC.RadioSend -> TrafficMonitorLayerC;
        MessageBufferLayerC.RadioReceive -> UniqueLayerC;
        MessageBufferLayerC.RadioState -> TrafficMonitorLayerC;
+       RadioChannel = MessageBufferLayerC;
+
+// -------- UniqueLayer receive part (wired twice)
 
        UniqueLayerC.SubReceive -> TrafficMonitorLayerC;
 
+// -------- Traffic Monitor
+
+       components TrafficMonitorLayerC;
        TrafficMonitorLayerC.Config -> RF212ActiveMessageP;
        TrafficMonitorLayerC.SubSend -> CollisionAvoidanceLayerC;
        TrafficMonitorLayerC.SubReceive -> CollisionAvoidanceLayerC;
        TrafficMonitorLayerC.SubState -> RF212DriverLayerC;
 
+// -------- CollisionAvoidance
+
+#ifdef SLOTTED_MAC
+       components SlottedCollisionLayerC as CollisionAvoidanceLayerC;
+#else
+       components RandomCollisionLayerC as CollisionAvoidanceLayerC;
+#endif
        CollisionAvoidanceLayerC.Config -> RF212ActiveMessageP;
        CollisionAvoidanceLayerC.SubSend -> SoftwareAckLayerC;
        CollisionAvoidanceLayerC.SubReceive -> SoftwareAckLayerC;
 
+// -------- SoftwareAcknowledgement
+
+       components SoftwareAckLayerC;
        SoftwareAckLayerC.Config -> RF212ActiveMessageP;
        SoftwareAckLayerC.SubSend -> CsmaLayerC;
        SoftwareAckLayerC.SubReceive -> RF212DriverLayerC;
+       PacketAcknowledgements = SoftwareAckLayerC;
+
+// -------- Carrier Sense
 
+       components new DummyLayerC() as CsmaLayerC;
        CsmaLayerC.Config -> RF212ActiveMessageP;
        CsmaLayerC -> RF212DriverLayerC.RadioSend;
        CsmaLayerC -> RF212DriverLayerC.RadioCCA;
 
+// -------- RF212 Driver
+
+       components RF212DriverLayerC;
+       RF212DriverLayerC.PacketRF212Metadata -> RF212ActiveMessageP;
        RF212DriverLayerC.RF212DriverConfig -> RF212ActiveMessageP;
+       RF212DriverLayerC.PacketTimeStamp -> TimeStampingLayerC;
+       PacketTransmitPower = RF212DriverLayerC.PacketTransmitPower;
+       PacketLinkQuality = RF212DriverLayerC.PacketLinkQuality;
+       PacketRSSI = RF212DriverLayerC.PacketRSSI;
+       LocalTimeRadio = RF212DriverLayerC;
+
+// -------- MetadataFlags
+
+       components MetadataFlagsLayerC;
+       MetadataFlagsLayerC.PacketFlagsMetadata -> RF212ActiveMessageP;
+
+// -------- TimeStamping
+
+       components TimeStampingLayerC;
+       TimeStampingLayerC.LocalTimeRadio -> RF212DriverLayerC;
+       TimeStampingLayerC.PacketTimeStampMetadata -> RF212ActiveMessageP;
+       PacketTimeStampRadio = TimeStampingLayerC;
+       PacketTimeStampMilli = TimeStampingLayerC;
 }
index f7332b2992fbda82eafe0533ad7305781ed3977e..e9f4cfcb0d6a045138979e0db12973ec1219b351 100644 (file)
@@ -21,7 +21,7 @@
  * Author: Miklos Maroti
  */
 
-#include <RF212Packet.h>
+#include <RF212ActiveMessage.h>
 #include <RadioConfig.h>
 #include <Tasklet.h>
 
@@ -38,13 +38,27 @@ module RF212ActiveMessageP
                interface SlottedCollisionConfig;
                interface ActiveMessageConfig;
                interface DummyConfig;
+
+               interface Packet;
+
+               interface PacketData<flags_metadata_t> as PacketFlagsMetadata;
+               interface PacketData<rf212_metadata_t> as PacketRF212Metadata;
+               interface PacketData<timestamp_metadata_t> as PacketTimeStampMetadata;
+
+#ifdef LOW_POWER_LISTENING
+               interface PacketData<lpl_metadata_t> as PacketLplMetadata;
+#endif
+#ifdef PACKET_LINK
+               interface PacketData<link_metadata_t> as PacketLinkMetadata;
+#endif
        }
 
        uses
        {
-               interface IEEE154Packet2;
-               interface Packet;
+               interface IEEE154PacketLayer;
                interface RadioAlarm;
+
+               interface PacketTimeStamp<TRadio, uint32_t>;
        }
 }
 
@@ -54,22 +68,17 @@ implementation
 
        async command uint8_t RF212DriverConfig.getLength(message_t* msg)
        {
-               return call IEEE154Packet2.getLength(msg);
+               return call IEEE154PacketLayer.getLength(msg);
        }
 
        async command void RF212DriverConfig.setLength(message_t* msg, uint8_t len)
        {
-               call IEEE154Packet2.setLength(msg, len);
+               call IEEE154PacketLayer.setLength(msg, len);
        }
 
        async command uint8_t* RF212DriverConfig.getPayload(message_t* msg)
        {
-               return ((uint8_t*)(call IEEE154Packet2.getHeader(msg))) + 1;
-       }
-
-       inline rf212packet_metadata_t* getMeta(message_t* msg)
-       {
-               return (rf212packet_metadata_t*)(msg->metadata);
+               return ((uint8_t*)(call IEEE154PacketLayer.getHeader(msg))) + 1;
        }
 
        async command uint8_t RF212DriverConfig.getHeaderLength()
@@ -86,42 +95,39 @@ implementation
 
        async command bool RF212DriverConfig.requiresRssiCca(message_t* msg)
        {
-               return call IEEE154Packet2.isDataFrame(msg);
+               return call IEEE154PacketLayer.isDataFrame(msg);
        }
 
 /*----------------- SoftwareAckConfig -----------------*/
 
        async command bool SoftwareAckConfig.requiresAckWait(message_t* msg)
        {
-               return call IEEE154Packet2.requiresAckWait(msg);
+               return call IEEE154PacketLayer.requiresAckWait(msg);
        }
 
        async command bool SoftwareAckConfig.isAckPacket(message_t* msg)
        {
-               return call IEEE154Packet2.isAckFrame(msg);
+               return call IEEE154PacketLayer.isAckFrame(msg);
        }
 
        async command bool SoftwareAckConfig.verifyAckPacket(message_t* data, message_t* ack)
        {
-               return call IEEE154Packet2.verifyAckReply(data, ack);
+               return call IEEE154PacketLayer.verifyAckReply(data, ack);
        }
 
-       async command bool SoftwareAckConfig.requiresAckReply(message_t* msg)
+       async command void SoftwareAckConfig.setAckRequired(message_t* msg, bool ack)
        {
-               return call IEEE154Packet2.requiresAckReply(msg);
+               call IEEE154PacketLayer.setAckRequired(msg, ack);
        }
 
-       async command void SoftwareAckConfig.createAckPacket(message_t* data, message_t* ack)
+       async command bool SoftwareAckConfig.requiresAckReply(message_t* msg)
        {
-               call IEEE154Packet2.createAckReply(data, ack);
+               return call IEEE154PacketLayer.requiresAckReply(msg);
        }
 
-       async command void SoftwareAckConfig.setAckReceived(message_t* msg, bool acked)
+       async command void SoftwareAckConfig.createAckPacket(message_t* data, message_t* ack)
        {
-               if( acked )
-                       getMeta(msg)->flags |= RF212PACKET_WAS_ACKED;
-               else
-                       getMeta(msg)->flags &= ~RF212PACKET_WAS_ACKED;
+               call IEEE154PacketLayer.createAckReply(data, ack);
        }
 
        async command uint16_t SoftwareAckConfig.getAckTimeout()
@@ -138,17 +144,17 @@ implementation
 
        async command uint8_t UniqueConfig.getSequenceNumber(message_t* msg)
        {
-               return call IEEE154Packet2.getDSN(msg);
+               return call IEEE154PacketLayer.getDSN(msg);
        }
 
        async command void UniqueConfig.setSequenceNumber(message_t* msg, uint8_t dsn)
        {
-               call IEEE154Packet2.setDSN(msg, dsn);
+               call IEEE154PacketLayer.setDSN(msg, dsn);
        }
 
        async command am_addr_t UniqueConfig.getSender(message_t* msg)
        {
-               return call IEEE154Packet2.getSrcAddr(msg);
+               return call IEEE154PacketLayer.getSrcAddr(msg);
        }
 
        tasklet_async command void UniqueConfig.reportChannelError()
@@ -161,7 +167,7 @@ implementation
        command error_t ActiveMessageConfig.checkPacket(message_t* msg)
        {
                // the user forgot to call clear, we should return EINVAL
-               if( ! call IEEE154Packet2.isDataFrame(msg) )
+               if( ! call IEEE154PacketLayer.isDataFrame(msg) )
                        call Packet.clear(msg);
 
                return SUCCESS;
@@ -171,7 +177,7 @@ implementation
 
        async command bool CsmaConfig.requiresSoftwareCCA(message_t* msg)
        {
-               return call IEEE154Packet2.isDataFrame(msg);
+               return call IEEE154PacketLayer.isDataFrame(msg);
        }
 
 /*----------------- TrafficMonitorConfig -----------------*/
@@ -196,13 +202,13 @@ implementation
                 * ack required: 8-16 byte separation, 11 bytes airtime, 5-10 bytes separation
                 */
 
-               uint8_t len = call IEEE154Packet2.getLength(msg);
-               return call IEEE154Packet2.getAckRequired(msg) ? len + 6 + 16 + 11 + 10 : len + 6 + 10;
+               uint8_t len = call IEEE154PacketLayer.getLength(msg);
+               return call IEEE154PacketLayer.getAckRequired(msg) ? len + 6 + 16 + 11 + 10 : len + 6 + 10;
        }
 
        async command am_addr_t TrafficMonitorConfig.getSender(message_t* msg)
        {
-               return call IEEE154Packet2.getSrcAddr(msg);
+               return call IEEE154PacketLayer.getSrcAddr(msg);
        }
 
        tasklet_async command void TrafficMonitorConfig.timerTick()
@@ -244,7 +250,7 @@ implementation
                time = call RadioAlarm.getNow();
 
                // estimated response time (download the message, etc) is 5-8 bytes
-               if( call IEEE154Packet2.requiresAckReply(msg) )
+               if( call IEEE154PacketLayer.requiresAckReply(msg) )
                        time += (uint16_t)(32 * (-5 + 16 + 11 + 5) * RADIO_ALARM_MICROSEC);
                else
                        time += (uint16_t)(32 * (-5 + 5) * RADIO_ALARM_MICROSEC);
@@ -269,13 +275,13 @@ implementation
        async command uint16_t SlottedCollisionConfig.getTransmitTime(message_t* msg)
        {
                // TODO: check if the timestamp is correct
-               return getMeta(msg)->timestamp;
+               return call PacketTimeStamp.timestamp(msg);
        }
 
        async command uint16_t SlottedCollisionConfig.getCollisionWindowStart(message_t* msg)
        {
                // the preamble (4 bytes), SFD (1 byte), plus two extra for safety
-               return getMeta(msg)->timestamp - (uint16_t)(7 * 32 * RADIO_ALARM_MICROSEC);
+               return (call PacketTimeStamp.timestamp(msg)) - (uint16_t)(7 * 32 * RADIO_ALARM_MICROSEC);
        }
 
        async command uint16_t SlottedCollisionConfig.getCollisionWindowLength(message_t* msg)
@@ -290,4 +296,86 @@ implementation
        async command void DummyConfig.nothing()
        {
        }
+
+/*----------------- Metadata -----------------*/
+
+       inline rf212packet_metadata_t* getMeta(message_t* msg)
+       {
+               return (rf212packet_metadata_t*)(msg->metadata);
+       }
+
+       async command flags_metadata_t* PacketFlagsMetadata.get(message_t* msg)
+       {
+               return &(getMeta(msg)->flags);
+       }
+
+       async command rf212_metadata_t* PacketRF212Metadata.get(message_t* msg)
+       {
+               return &(getMeta(msg)->rf212);
+       }
+
+       async command timestamp_metadata_t* PacketTimeStampMetadata.get(message_t* msg)
+       {
+               return &(getMeta(msg)->timestamp);
+       }
+
+#ifdef LOW_POWER_LISTENING
+       async command lpl_metadata_t* PacketLplMetadata.get(message_t* msg)
+       {
+               return &(getMeta(msg)->lpl);
+       }
+#endif
+
+#ifdef PACKET_LINK
+       async command link_metadata_t* PacketLinkMetadata.get(message_t* msg)
+       {
+               return &(getMeta(msg)->link);
+       }
+#endif
+
+/*----------------- Packet -----------------*/
+
+       enum
+       {
+               PACKET_LENGTH_INCREASE =
+                       sizeof(rf212packet_header_t) - 1        // the 8-bit length field is not counted
+                       + sizeof(ieee154_footer_t),             // the CRC is not stored in memory
+       };
+
+       command void Packet.clear(message_t* msg)
+       {
+               signal PacketFlagsMetadata.clear(msg);
+               signal PacketRF212Metadata.clear(msg);
+               signal PacketTimeStampMetadata.clear(msg);
+#ifdef LOW_POWER_LISTENING
+               signal PacketLplMetadata.clear(msg);
+#endif
+#ifdef PACKET_LINK
+               signal PacketLinkMetadata.clear(msg);
+#endif
+               call IEEE154PacketLayer.createDataFrame(msg);
+       }
+
+       inline command void Packet.setPayloadLength(message_t* msg, uint8_t len)
+       {
+               call IEEE154PacketLayer.setLength(msg, len + PACKET_LENGTH_INCREASE);
+       }
+
+       inline command uint8_t Packet.payloadLength(message_t* msg)
+       {
+               return call IEEE154PacketLayer.getLength(msg) - PACKET_LENGTH_INCREASE;
+       }
+
+       inline command uint8_t Packet.maxPayloadLength()
+       {
+               return TOSH_DATA_LENGTH;
+       }
+
+       command void* Packet.getPayload(message_t* msg, uint8_t len)
+       {
+               if( len > TOSH_DATA_LENGTH )
+                       return NULL;
+
+               return msg->data;
+       }
 }
diff --git a/tos/chips/rf2xx/rf212/RF212DriverLayer.h b/tos/chips/rf2xx/rf212/RF212DriverLayer.h
new file mode 100644 (file)
index 0000000..0224247
--- /dev/null
@@ -0,0 +1,172 @@
+/*
+ * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
+ * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ * 
+ * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
+ * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+ *
+ * Author: Miklos Maroti
+ */
+
+#ifndef __RF212DRIVERLAYER_H__
+#define __RF212DRIVERLAYER_H__
+
+typedef struct rf212_metadata_t
+{
+       uint8_t lqi;
+       union
+       {
+               uint8_t power;
+               uint8_t rssi;
+       };
+} rf212_metadata_t;
+
+enum rf212_registers_enum
+{
+       RF212_TRX_STATUS = 0x01,
+       RF212_TRX_STATE = 0x02,
+       RF212_TRX_CTRL_0 = 0x03,
+       RF212_TRX_CTRL_1 = 0x04,
+       RF212_PHY_TX_PWR = 0x05,
+       RF212_PHY_RSSI = 0x06,
+       RF212_PHY_ED_LEVEL = 0x07,
+       RF212_PHY_CC_CCA = 0x08,
+       RF212_CCA_THRES = 0x09,
+       RF212_IRQ_MASK = 0x0E,
+       RF212_IRQ_STATUS = 0x0F,
+       RF212_VREG_CTRL = 0x10,
+       RF212_BATMON = 0x11,
+       RF212_XOSC_CTRL = 0x12,
+       RF212_PLL_CF = 0x1A,
+       RF212_PLL_DCU = 0x1B,
+       RF212_PART_NUM = 0x1C,
+       RF212_VERSION_NUM = 0x1D,
+       RF212_MAN_ID_0 = 0x1E,
+       RF212_MAN_ID_1 = 0x1F,
+       RF212_SHORT_ADDR_0 = 0x20,
+       RF212_SHORT_ADDR_1 = 0x21,
+       RF212_PAN_ID_0 = 0x22,
+       RF212_PAN_ID_1 = 0x23,
+       RF212_IEEE_ADDR_0 = 0x24,
+       RF212_IEEE_ADDR_1 = 0x25,
+       RF212_IEEE_ADDR_2 = 0x26,
+       RF212_IEEE_ADDR_3 = 0x27,
+       RF212_IEEE_ADDR_4 = 0x28,
+       RF212_IEEE_ADDR_5 = 0x29,
+       RF212_IEEE_ADDR_6 = 0x2A,
+       RF212_IEEE_ADDR_7 = 0x2B,
+       RF212_XAH_CTRL = 0x2C,
+       RF212_CSMA_SEED_0 = 0x2D,
+       RF212_CSMA_SEED_1 = 0x2E,
+};
+
+enum rf212_trx_status_enums
+{
+       RF212_CCA_DONE = 1 << 7,
+       RF212_CCA_STATUS = 1 << 6,
+       RF212_TRX_STATUS_MASK = 0x1F,
+       RF212_P_ON = 0,
+       RF212_BUSY_RX = 1,
+       RF212_BUSY_TX = 2,
+       RF212_RX_ON = 6,
+       RF212_TRX_OFF = 8,
+       RF212_PLL_ON = 9,
+       RF212_SLEEP = 15,
+       RF212_BUSY_RX_AACK = 16,
+       RF212_BUSR_TX_ARET = 17,
+       RF212_RX_AACK_ON = 22,
+       RF212_TX_ARET_ON = 25,
+       RF212_RX_ON_NOCLK = 28,
+       RF212_AACK_ON_NOCLK = 29,
+       RF212_BUSY_RX_AACK_NOCLK = 30,
+       RF212_STATE_TRANSITION_IN_PROGRESS = 31,
+};
+
+enum rf212_trx_state_enums
+{
+       RF212_TRAC_STATUS_MASK = 0xE0,
+       RF212_TRAC_SUCCESS = 0,
+       RF212_TRAC_CHANNEL_ACCESS_FAILURE = 3 << 5,
+       RF212_TRAC_NO_ACK = 5 << 5,
+       RF212_TRX_CMD_MASK = 0x1F,
+       RF212_NOP = 0,
+       RF212_TX_START = 2,
+       RF212_FORCE_TRX_OFF = 3,
+};
+
+enum rf212_phy_rssi_enums
+{
+       RF212_RX_CRC_VALID = 1 << 7,
+       RF212_RSSI_MASK = 0x1F,
+};
+
+enum rf212_phy_cc_cca_enums
+{
+       RF212_CCA_REQUEST = 1 << 7,
+       RF212_CCA_MODE_0 = 0 << 5,
+       RF212_CCA_MODE_1 = 1 << 5,
+       RF212_CCA_MODE_2 = 2 << 5,
+       RF212_CCA_MODE_3 = 3 << 5,
+       RF212_CHANNEL_DEFAULT = 11,
+       RF212_CHANNEL_MASK = 0x1F,
+};
+
+enum rf212_irq_register_enums
+{
+       RF212_IRQ_BAT_LOW = 1 << 7,
+       RF212_IRQ_TRX_UR = 1 << 6,
+       RF212_IRQ_AMI = 1 << 5,
+       RF212_IRQ_CCA_ED_DONE = 1 << 4,
+       RF212_IRQ_TRX_END = 1 << 3,
+       RF212_IRQ_RX_START = 1 << 2,
+       RF212_IRQ_PLL_UNLOCK = 1 << 1,
+       RF212_IRQ_PLL_LOCK = 1 << 0,
+};
+
+enum rf212_batmon_enums
+{
+       RF212_BATMON_OK = 1 << 5,
+       RF212_BATMON_VHR = 1 << 4,
+       RF212_BATMON_VTH_MASK = 0x0F,
+};
+
+enum rf212_vreg_ctrl_enums
+{
+       RF212_AVREG_EXT = 1 << 7,
+       RF212_AVDD_OK = 1 << 6,
+       RF212_DVREG_EXT = 1 << 3,
+       RF212_DVDD_OK = 1 << 2,
+};
+
+enum rf212_xosc_ctrl_enums
+{
+       RF212_XTAL_MODE_OFF = 0 << 4,
+       RF212_XTAL_MODE_EXTERNAL = 4 << 4,
+       RF212_XTAL_MODE_INTERNAL = 15 << 4,
+};
+
+enum rf212_spi_command_enums
+{
+       RF212_CMD_REGISTER_READ = 0x80,
+       RF212_CMD_REGISTER_WRITE = 0xC0,
+       RF212_CMD_REGISTER_MASK = 0x3F,
+       RF212_CMD_FRAME_READ = 0x20,
+       RF212_CMD_FRAME_WRITE = 0x60,
+       RF212_CMD_SRAM_READ = 0x00,
+       RF212_CMD_SRAM_WRITE = 0x40,
+};
+
+#endif//__RF212DRIVERLAYER_H__
index d847e6febd8869954c0b8bd2a52dd266eaf42bc9..5197b694f81eb8270cf84717f5b3bf884fe451a9 100644 (file)
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2007, Vanderbilt University
+ * Copyright (c) 2009, Vanderbilt University
  * All rights reserved.
  *
  * Permission to use, copy, modify, and distribute this software and its
@@ -21,6 +21,9 @@
  * Author: Miklos Maroti
  */
 
+#include <RadioConfig.h>
+#include <RF212DriverLayer.h>
+
 configuration RF212DriverLayerC
 {
        provides
@@ -29,28 +32,53 @@ configuration RF212DriverLayerC
                interface RadioSend;
                interface RadioReceive;
                interface RadioCCA;
+
+               interface PacketField<uint8_t> as PacketTransmitPower;
+               interface PacketField<uint8_t> as PacketRSSI;
+               interface PacketField<uint8_t> as PacketTimeSyncOffset;
+               interface PacketField<uint8_t> as PacketLinkQuality;
+
+               interface LocalTime<TRadio> as LocalTimeRadio;
        }
 
-       uses interface RF212DriverConfig;
+       uses
+       {
+               interface RF212DriverConfig;
+               interface PacketTimeStamp<TRadio, uint32_t>;
+               interface PacketData<rf212_metadata_t> as PacketRF212Metadata;
+       }
 }
 
 implementation
 {
-       components RF212DriverLayerP, HplRF212C, BusyWaitMicroC, TaskletC, MainC, RadioAlarmC, RF212PacketC, LocalTimeMicroC as LocalTimeRadioC;
+       components RF212DriverLayerP, HplRF212C, BusyWaitMicroC, TaskletC, MainC, RadioAlarmC;
 
        RadioState = RF212DriverLayerP;
        RadioSend = RF212DriverLayerP;
        RadioReceive = RF212DriverLayerP;
        RadioCCA = RF212DriverLayerP;
 
+       LocalTimeRadio = HplRF212C;
+
        RF212DriverConfig = RF212DriverLayerP;
+       PacketRF212Metadata = RF212DriverLayerP;
+
+       PacketTransmitPower = RF212DriverLayerP.PacketTransmitPower;
+       components new MetadataFlagC() as TransmitPowerFlagC;
+       RF212DriverLayerP.TransmitPowerFlag -> TransmitPowerFlagC;
+
+       PacketRSSI = RF212DriverLayerP.PacketRSSI;
+       components new MetadataFlagC() as RSSIFlagC;
+       RF212DriverLayerP.RSSIFlag -> RSSIFlagC;
+
+       PacketTimeSyncOffset = RF212DriverLayerP.PacketTimeSyncOffset;
+       components new MetadataFlagC() as TimeSyncFlagC;
+       RF212DriverLayerP.TimeSyncFlag -> TimeSyncFlagC;
+
+       PacketLinkQuality = RF212DriverLayerP.PacketLinkQuality;
+       PacketTimeStamp = RF212DriverLayerP.PacketTimeStamp;
 
-       RF212DriverLayerP.PacketLinkQuality -> RF212PacketC.PacketLinkQuality;
-       RF212DriverLayerP.PacketTransmitPower -> RF212PacketC.PacketTransmitPower;
-       RF212DriverLayerP.PacketRSSI -> RF212PacketC.PacketRSSI;
-       RF212DriverLayerP.PacketTimeSyncOffset -> RF212PacketC.PacketTimeSyncOffset;
-       RF212DriverLayerP.PacketTimeStamp -> RF212PacketC;
-       RF212DriverLayerP.LocalTime -> LocalTimeRadioC;
+       RF212DriverLayerP.LocalTime -> HplRF212C;
 
        RF212DriverLayerP.RadioAlarm -> RadioAlarmC.RadioAlarm[unique("RadioAlarm")];
        RadioAlarmC.Alarm -> HplRF212C.Alarm;
index 2a9d35a34987c6529e300944630c4f6daccea69c..6950dd6f6f5edab572dc283a34817b7f89c39db2 100644 (file)
@@ -21,7 +21,7 @@
  * Author: Miklos Maroti
  */
 
-#include <RF212.h>
+#include <RF212DriverLayer.h>
 #include <Tasklet.h>
 #include <RadioAssert.h>
 #include <GenericTimeSyncMessage.h>
@@ -38,6 +38,11 @@ module RF212DriverLayerP
                interface RadioSend;
                interface RadioReceive;
                interface RadioCCA;
+
+               interface PacketField<uint8_t> as PacketTransmitPower;
+               interface PacketField<uint8_t> as PacketRSSI;
+               interface PacketField<uint8_t> as PacketTimeSyncOffset;
+               interface PacketField<uint8_t> as PacketLinkQuality;
        }
 
        uses
@@ -53,16 +58,17 @@ module RF212DriverLayerP
                interface GpioCapture as IRQ;
 
                interface BusyWait<TMicro, uint16_t>;
+               interface LocalTime<TRadio>;
 
-               interface PacketField<uint8_t> as PacketLinkQuality;
-               interface PacketField<uint8_t> as PacketTransmitPower;
-               interface PacketField<uint8_t> as PacketRSSI;
-               interface PacketField<uint8_t> as PacketTimeSyncOffset;
+               interface RF212DriverConfig;
+
+               interface PacketData<rf212_metadata_t> as PacketRF212Metadata;
+               interface PacketFlag as TransmitPowerFlag;
+               interface PacketFlag as RSSIFlag;
+               interface PacketFlag as TimeSyncFlag;
 
                interface PacketTimeStamp<TRadio, uint32_t>;
-               interface LocalTime<TRadio>;
 
-               interface RF212DriverConfig;
                interface Tasklet;
                interface RadioAlarm;
 
@@ -548,7 +554,7 @@ implementation
        inline void downloadMessage()
        {
                uint8_t length;
-               uint8_t crc;
+               uint8_t crc = 0;
 
                call SELN.clr();
                call FastSpiByte.write(RF212_CMD_FRAME_READ);
@@ -608,7 +614,7 @@ implementation
                        call DiagMsg.str("rx");
                        call DiagMsg.uint32(call PacketTimeStamp.isValid(rxMsg) ? call PacketTimeStamp.timestamp(rxMsg) : 0);
                        call DiagMsg.uint16(call RadioAlarm.getNow());
-                       call DiagMsg.uint8(crc != 0);
+                       call DiagMsg.uint8(crc == 0);
                        call DiagMsg.uint8(length);
                        call DiagMsg.hex8s(call RF212DriverConfig.getPayload(rxMsg), length - 2);
                        call DiagMsg.send();
@@ -816,4 +822,112 @@ implementation
                if( cmd == CMD_NONE )
                        call SpiResource.release();
        }
+
+/*----------------- PACKET -----------------*/
+
+       async event void PacketRF212Metadata.clear(message_t* msg)
+       {
+       }
+
+// --- TransmitPower
+
+       async command bool PacketTransmitPower.isSet(message_t* msg)
+       {
+               return call TransmitPowerFlag.get(msg);
+       }
+
+       async command uint8_t PacketTransmitPower.get(message_t* msg)
+       {
+               return (call PacketRF212Metadata.get(msg))->power;
+       }
+
+       async command void PacketTransmitPower.clear(message_t* msg)
+       {
+               call TransmitPowerFlag.clear(msg);
+       }
+
+       async command void PacketTransmitPower.set(message_t* msg, uint8_t value)
+       {
+               call TransmitPowerFlag.set(msg);
+               (call PacketRF212Metadata.get(msg))->power = value;
+       }
+
+// --- RSSI
+
+       async command bool PacketRSSI.isSet(message_t* msg)
+       {
+               return call RSSIFlag.get(msg);
+       }
+
+       async command uint8_t PacketRSSI.get(message_t* msg)
+       {
+               return (call PacketRF212Metadata.get(msg))->rssi;
+       }
+
+       async command void PacketRSSI.clear(message_t* msg)
+       {
+               call RSSIFlag.clear(msg);
+       }
+
+       async command void PacketRSSI.set(message_t* msg, uint8_t value)
+       {
+               // just to be safe if the user fails to clear the packet
+               call TransmitPowerFlag.clear(msg);
+
+               call RSSIFlag.set(msg);
+               (call PacketRF212Metadata.get(msg))->rssi = value;
+       }
+
+// --- TimeSyncOffset
+
+       enum
+       {
+               PACKET_LENGTH_INCREASE =
+                       sizeof(rf212packet_header_t) - 1        // the 8-bit length field is not counted
+                       + sizeof(ieee154_footer_t),             // the CRC is not stored in memory
+       };
+
+       async command bool PacketTimeSyncOffset.isSet(message_t* msg)
+       {
+               return call TimeSyncFlag.get(msg);
+       }
+
+       async command uint8_t PacketTimeSyncOffset.get(message_t* msg)
+       {
+               return call RF212DriverConfig.getLength(msg) - PACKET_LENGTH_INCREASE - sizeof(timesync_absolute_t);
+       }
+
+       async command void PacketTimeSyncOffset.clear(message_t* msg)
+       {
+               call TimeSyncFlag.clear(msg);
+       }
+
+       async command void PacketTimeSyncOffset.set(message_t* msg, uint8_t value)
+       {
+               // we do not store the value, the time sync field is always the last 4 bytes
+               ASSERT( call RF212DriverConfig.getLength(msg) - PACKET_LENGTH_INCREASE - sizeof(timesync_absolute_t) == value );
+
+               call TimeSyncFlag.set(msg);
+       }
+
+// --- LinkQuality
+
+       async command bool PacketLinkQuality.isSet(message_t* msg)
+       {
+               return TRUE;
+       }
+
+       async command uint8_t PacketLinkQuality.get(message_t* msg)
+       {
+               return (call PacketRF212Metadata.get(msg))->lqi;
+       }
+
+       async command void PacketLinkQuality.clear(message_t* msg)
+       {
+       }
+
+       async command void PacketLinkQuality.set(message_t* msg, uint8_t value)
+       {
+               (call PacketRF212Metadata.get(msg))->lqi = value;
+       }
 }
diff --git a/tos/chips/rf2xx/rf212/RF212Packet.h b/tos/chips/rf2xx/rf212/RF212Packet.h
deleted file mode 100644 (file)
index ed37875..0000000
+++ /dev/null
@@ -1,63 +0,0 @@
-/*
- * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
- * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
- * 
- * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
- * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
- *
- * Author: Miklos Maroti
- */
-
-#ifndef __RF212PACKET_H__
-#define __RF212PACKET_H__
-
-#include <IEEE154Packet2.h>
-#include <PacketLinkLayer.h>
-
-typedef ieee154_header_t rf212packet_header_t;
-
-typedef nx_struct rf212packet_footer_t
-{
-       // the time stamp is not recorded here, time stamped messaged cannot have max length
-} rf212packet_footer_t;
-
-typedef struct rf212packet_metadata_t
-{
-       uint8_t flags;
-       uint8_t lqi;
-       uint8_t power;                          // shared between TXPOWER and RSSI
-#ifdef LOW_POWER_LISTENING
-       uint16_t lpl_sleepint;
-#endif
-#ifdef PACKET_LINK
-       packet_link_metadata_t packet_link;
-#endif
-       uint32_t timestamp;
-} rf212packet_metadata_t;
-
-enum rf212packet_metadata_flags
-{
-       RF212PACKET_WAS_ACKED = 0x01,           // PacketAcknowledgements
-       RF212PACKET_TIMESTAMP = 0x02,           // PacketTimeStamp
-       RF212PACKET_TXPOWER = 0x04,             // PacketTransmitPower
-       RF212PACKET_RSSI = 0x08,                // PacketRSSI
-       RF212PACKET_TIMESYNC = 0x10,            // PacketTimeSync (update timesync_footer)
-       RF212PACKET_LPL_SLEEPINT = 0x20,        // LowPowerListening
-
-       RF212PACKET_CLEAR_METADATA = 0x00,
-};
-
-#endif//__RF212PACKET_H__
diff --git a/tos/chips/rf2xx/rf212/RF212PacketC.nc b/tos/chips/rf2xx/rf212/RF212PacketC.nc
deleted file mode 100644 (file)
index 89f8245..0000000
+++ /dev/null
@@ -1,69 +0,0 @@
-/*
- * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
- * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
- * 
- * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
- * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
- *
- * Author: Miklos Maroti
- */
-
-configuration RF212PacketC
-{
-       provides
-       {
-               interface Packet;
-               interface AMPacket;
-               interface PacketAcknowledgements;
-               interface PacketField<uint8_t> as PacketLinkQuality;
-               interface PacketField<uint8_t> as PacketTransmitPower;
-               interface PacketField<uint8_t> as PacketRSSI;
-               interface PacketField<uint16_t> as PacketSleepInterval;
-               interface PacketField<uint8_t> as PacketTimeSyncOffset;
-
-               interface PacketTimeStamp<TRadio, uint32_t> as PacketTimeStampRadio;
-               interface PacketTimeStamp<TMilli, uint32_t> as PacketTimeStampMilli;
-#ifdef PACKET_LINK
-               interface PacketData<packet_link_metadata_t> as PaketLinkMetadata;
-#endif
-       }
-}
-
-implementation
-{
-       components RF212PacketP, IEEE154Packet2C, LocalTimeMicroC, LocalTimeMilliC;
-
-       RF212PacketP.IEEE154Packet2 -> IEEE154Packet2C;
-       RF212PacketP.LocalTimeRadio -> LocalTimeMicroC;
-       RF212PacketP.LocalTimeMilli -> LocalTimeMilliC;
-
-       Packet = RF212PacketP;
-       AMPacket = IEEE154Packet2C;
-
-       PacketAcknowledgements  = RF212PacketP;
-       PacketLinkQuality       = RF212PacketP.PacketLinkQuality;
-       PacketTransmitPower     = RF212PacketP.PacketTransmitPower;
-       PacketRSSI              = RF212PacketP.PacketRSSI;
-       PacketSleepInterval     = RF212PacketP.PacketSleepInterval;
-       PacketTimeSyncOffset    = RF212PacketP.PacketTimeSyncOffset;
-
-       PacketTimeStampRadio    = RF212PacketP;
-       PacketTimeStampMilli    = RF212PacketP;
-
-#ifdef PACKET_LINK
-       PaketLinkMetadata       = RF212PacketP;
-#endif
-}
diff --git a/tos/chips/rf2xx/rf212/RF212PacketP.nc b/tos/chips/rf2xx/rf212/RF212PacketP.nc
deleted file mode 100644 (file)
index 1658168..0000000
+++ /dev/null
@@ -1,305 +0,0 @@
-/*
- * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
- * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
- *
- * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
- * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
- *
- * Author: Miklos Maroti
- */
-
-#include <RF212Packet.h>
-#include <GenericTimeSyncMessage.h>
-#include <RadioConfig.h>
-#include <PacketLinkLayer.h>
-
-module RF212PacketP
-{
-       provides
-       {
-               interface PacketAcknowledgements;
-               interface Packet;
-               interface PacketField<uint8_t> as PacketLinkQuality;
-               interface PacketField<uint8_t> as PacketTransmitPower;
-               interface PacketField<uint8_t> as PacketRSSI;
-               interface PacketField<uint16_t> as PacketSleepInterval;
-               interface PacketField<uint8_t> as PacketTimeSyncOffset;
-
-               interface PacketTimeStamp<TRadio, uint32_t> as PacketTimeStampRadio;
-               interface PacketTimeStamp<TMilli, uint32_t> as PacketTimeStampMilli;
-
-#ifdef PACKET_LINK
-               interface PacketData<packet_link_metadata_t> as PacketLinkMetadata;
-#endif
-       }
-
-       uses
-       {
-               interface IEEE154Packet2;
-
-               interface LocalTime<TRadio> as LocalTimeRadio;
-               interface LocalTime<TMilli> as LocalTimeMilli;
-       }
-}
-
-implementation
-{
-       enum
-       {
-               PACKET_LENGTH_INCREASE =
-                       sizeof(rf212packet_header_t) - 1        // the 8-bit length field is not counted
-                       + sizeof(ieee154_footer_t),             // the CRC is not stored in memory
-       };
-
-       inline rf212packet_metadata_t* getMeta(message_t* msg)
-       {
-               return (rf212packet_metadata_t*)(msg->metadata);
-       }
-
-/*----------------- Packet -----------------*/
-
-       command void Packet.clear(message_t* msg)
-       {
-               call IEEE154Packet2.createDataFrame(msg);
-
-               getMeta(msg)->flags = RF212PACKET_CLEAR_METADATA;
-       }
-
-       inline command void Packet.setPayloadLength(message_t* msg, uint8_t len)
-       {
-               call IEEE154Packet2.setLength(msg, len + PACKET_LENGTH_INCREASE);
-       }
-
-       inline command uint8_t Packet.payloadLength(message_t* msg)
-       {
-               return call IEEE154Packet2.getLength(msg) - PACKET_LENGTH_INCREASE;
-       }
-
-       inline command uint8_t Packet.maxPayloadLength()
-       {
-               return TOSH_DATA_LENGTH;
-       }
-
-       command void* Packet.getPayload(message_t* msg, uint8_t len)
-       {
-               if( len > TOSH_DATA_LENGTH )
-                       return NULL;
-
-               return msg->data;
-       }
-
-/*----------------- PacketAcknowledgements -----------------*/
-
-       async command error_t PacketAcknowledgements.requestAck(message_t* msg)
-       {
-               call IEEE154Packet2.setAckRequired(msg, TRUE);
-
-               return SUCCESS;
-       }
-
-       async command error_t PacketAcknowledgements.noAck(message_t* msg)
-       {
-               call IEEE154Packet2.setAckRequired(msg, FALSE);
-
-               return SUCCESS;
-       }
-
-       async command bool PacketAcknowledgements.wasAcked(message_t* msg)
-       {
-               return getMeta(msg)->flags & RF212PACKET_WAS_ACKED;
-       }
-
-/*----------------- PacketLinkQuality -----------------*/
-
-       async command bool PacketLinkQuality.isSet(message_t* msg)
-       {
-               return TRUE;
-       }
-
-       async command uint8_t PacketLinkQuality.get(message_t* msg)
-       {
-               return getMeta(msg)->lqi;
-       }
-
-       async command void PacketLinkQuality.clear(message_t* msg)
-       {
-       }
-
-       async command void PacketLinkQuality.set(message_t* msg, uint8_t value)
-       {
-               getMeta(msg)->lqi = value;
-       }
-
-/*----------------- PacketTimeStampRadio -----------------*/
-
-       async command bool PacketTimeStampRadio.isValid(message_t* msg)
-       {
-               return getMeta(msg)->flags & RF212PACKET_TIMESTAMP;
-       }
-
-       async command uint32_t PacketTimeStampRadio.timestamp(message_t* msg)
-       {
-               return getMeta(msg)->timestamp;
-       }
-
-       async command void PacketTimeStampRadio.clear(message_t* msg)
-       {
-               getMeta(msg)->flags &= ~RF212PACKET_TIMESTAMP;
-       }
-
-       async command void PacketTimeStampRadio.set(message_t* msg, uint32_t value)
-       {
-               getMeta(msg)->flags |= RF212PACKET_TIMESTAMP;
-               getMeta(msg)->timestamp = value;
-       }
-
-/*----------------- PacketTimeStampMilli -----------------*/
-
-       async command bool PacketTimeStampMilli.isValid(message_t* msg)
-       {
-               return call PacketTimeStampRadio.isValid(msg);
-       }
-
-       async command uint32_t PacketTimeStampMilli.timestamp(message_t* msg)
-       {
-               int32_t offset = call PacketTimeStampRadio.timestamp(msg) - call LocalTimeRadio.get();
-
-               return (offset >> RADIO_ALARM_MILLI_EXP) + call LocalTimeMilli.get();
-       }
-
-       async command void PacketTimeStampMilli.clear(message_t* msg)
-       {
-               call PacketTimeStampRadio.clear(msg);
-       }
-
-       async command void PacketTimeStampMilli.set(message_t* msg, uint32_t value)
-       {
-               int32_t offset = (value - call LocalTimeMilli.get()) << RADIO_ALARM_MILLI_EXP;
-
-               call PacketTimeStampRadio.set(msg, offset + call LocalTimeRadio.get());
-       }
-
-/*----------------- PacketTransmitPower -----------------*/
-
-       async command bool PacketTransmitPower.isSet(message_t* msg)
-       {
-               return getMeta(msg)->flags & RF212PACKET_TXPOWER;
-       }
-
-       async command uint8_t PacketTransmitPower.get(message_t* msg)
-       {
-               return getMeta(msg)->power;
-       }
-
-       async command void PacketTransmitPower.clear(message_t* msg)
-       {
-               getMeta(msg)->flags &= ~RF212PACKET_TXPOWER;
-       }
-
-       async command void PacketTransmitPower.set(message_t* msg, uint8_t value)
-       {
-               getMeta(msg)->flags &= ~RF212PACKET_RSSI;
-               getMeta(msg)->flags |= RF212PACKET_TXPOWER;
-               getMeta(msg)->power = value;
-       }
-
-/*----------------- PacketRSSI -----------------*/
-
-       async command bool PacketRSSI.isSet(message_t* msg)
-       {
-               return getMeta(msg)->flags & RF212PACKET_RSSI;
-       }
-
-       async command uint8_t PacketRSSI.get(message_t* msg)
-       {
-               return getMeta(msg)->power;
-       }
-
-       async command void PacketRSSI.clear(message_t* msg)
-       {
-               getMeta(msg)->flags &= ~RF212PACKET_RSSI;
-       }
-
-       async command void PacketRSSI.set(message_t* msg, uint8_t value)
-       {
-               getMeta(msg)->flags &= ~RF212PACKET_TXPOWER;
-               getMeta(msg)->flags |= RF212PACKET_RSSI;
-               getMeta(msg)->power = value;
-       }
-
-/*----------------- PacketTimeSyncOffset -----------------*/
-
-       async command bool PacketTimeSyncOffset.isSet(message_t* msg)
-       {
-               return getMeta(msg)->flags & RF212PACKET_TIMESYNC;
-       }
-
-       async command uint8_t PacketTimeSyncOffset.get(message_t* msg)
-       {
-               return call IEEE154Packet2.getLength(msg) - PACKET_LENGTH_INCREASE - sizeof(timesync_absolute_t);
-       }
-
-       async command void PacketTimeSyncOffset.clear(message_t* msg)
-       {
-               getMeta(msg)->flags &= ~RF212PACKET_TIMESYNC;
-       }
-
-       async command void PacketTimeSyncOffset.set(message_t* msg, uint8_t value)
-       {
-               // the value is ignored, the offset always points to the timesync footer at the end of the payload
-               getMeta(msg)->flags |= RF212PACKET_TIMESYNC;
-       }
-
-/*----------------- PacketSleepInterval -----------------*/
-
-       async command bool PacketSleepInterval.isSet(message_t* msg)
-       {
-               return getMeta(msg)->flags & RF212PACKET_LPL_SLEEPINT;
-       }
-
-       async command uint16_t PacketSleepInterval.get(message_t* msg)
-       {
-#ifdef LOW_POWER_LISTENING
-               return getMeta(msg)->lpl_sleepint;
-#else
-               return 0;
-#endif
-       }
-
-       async command void PacketSleepInterval.clear(message_t* msg)
-       {
-               getMeta(msg)->flags &= ~RF212PACKET_LPL_SLEEPINT;
-       }
-
-       async command void PacketSleepInterval.set(message_t* msg, uint16_t value)
-       {
-               getMeta(msg)->flags |= RF212PACKET_LPL_SLEEPINT;
-
-#ifdef LOW_POWER_LISTENING
-               getMeta(msg)->lpl_sleepint = value;
-#endif
-       }
-
-/*----------------- PacketLinkMetadata -----------------*/
-#ifdef PACKET_LINK
-
-       async command packet_link_metadata_t* PacketLinkMetadata.getData(message_t* msg)
-       {
-               return &(getMeta(msg)->packet_link);
-       }
-
-#endif
-}
diff --git a/tos/chips/rf2xx/rf230/RF230.h b/tos/chips/rf2xx/rf230/RF230.h
deleted file mode 100644 (file)
index dd386a1..0000000
+++ /dev/null
@@ -1,152 +0,0 @@
-/*
- * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
- * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
- * 
- * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
- * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
- *
- * Author: Miklos Maroti
- */
-
-#ifndef __RF230_H__
-#define __RF230_H__
-
-enum rf230_registers_enum
-{
-       RF230_TRX_STATUS = 0x01,
-       RF230_TRX_STATE = 0x02,
-       RF230_TRX_CTRL_0 = 0x03,
-       RF230_PHY_TX_PWR = 0x05,
-       RF230_PHY_RSSI = 0x06,
-       RF230_PHY_ED_LEVEL = 0x07,
-       RF230_PHY_CC_CCA = 0x08,
-       RF230_CCA_THRES = 0x09,
-       RF230_IRQ_MASK = 0x0E,
-       RF230_IRQ_STATUS = 0x0F,
-       RF230_VREG_CTRL = 0x10,
-       RF230_BATMON = 0x11,
-       RF230_XOSC_CTRL = 0x12,
-       RF230_PLL_CF = 0x1A,
-       RF230_PLL_DCU = 0x1B,
-       RF230_PART_NUM = 0x1C,
-       RF230_VERSION_NUM = 0x1D,
-       RF230_MAN_ID_0 = 0x1E,
-       RF230_MAN_ID_1 = 0x1F,
-       RF230_SHORT_ADDR_0 = 0x20,
-       RF230_SHORT_ADDR_1 = 0x21,
-       RF230_PAN_ID_0 = 0x22,
-       RF230_PAN_ID_1 = 0x23,
-       RF230_IEEE_ADDR_0 = 0x24,
-       RF230_IEEE_ADDR_1 = 0x25,
-       RF230_IEEE_ADDR_2 = 0x26,
-       RF230_IEEE_ADDR_3 = 0x27,
-       RF230_IEEE_ADDR_4 = 0x28,
-       RF230_IEEE_ADDR_5 = 0x29,
-       RF230_IEEE_ADDR_6 = 0x2A,
-       RF230_IEEE_ADDR_7 = 0x2B,
-       RF230_XAH_CTRL = 0x2C,
-       RF230_CSMA_SEED_0 = 0x2D,
-       RF230_CSMA_SEED_1 = 0x2E,
-};
-
-enum rf230_trx_register_enums
-{
-       RF230_CCA_DONE = 1 << 7,
-       RF230_CCA_STATUS = 1 << 6,
-       RF230_TRX_STATUS_MASK = 0x1F,
-       RF230_P_ON = 0,
-       RF230_BUSY_RX = 1,
-       RF230_BUSY_TX = 2,
-       RF230_RX_ON = 6,
-       RF230_TRX_OFF = 8,
-       RF230_PLL_ON = 9,
-       RF230_SLEEP = 15,
-       RF230_BUSY_RX_AACK = 16,
-       RF230_BUSR_TX_ARET = 17,
-       RF230_RX_AACK_ON = 22,
-       RF230_TX_ARET_ON = 25,
-       RF230_RX_ON_NOCLK = 28,
-       RF230_AACK_ON_NOCLK = 29,
-       RF230_BUSY_RX_AACK_NOCLK = 30,
-       RF230_STATE_TRANSITION_IN_PROGRESS = 31,
-       RF230_TRAC_STATUS_MASK = 0xE0,
-       RF230_TRAC_SUCCESS = 0,
-       RF230_TRAC_CHANNEL_ACCESS_FAILURE = 3 << 5,
-       RF230_TRAC_NO_ACK = 5 << 5,
-       RF230_TRX_CMD_MASK = 0x1F,
-       RF230_NOP = 0,
-       RF230_TX_START = 2,
-       RF230_FORCE_TRX_OFF = 3,
-};
-
-enum rf230_phy_register_enums
-{
-       RF230_TX_AUTO_CRC_ON = 1 << 7,
-       RF230_TX_PWR_MASK = 0x0F,
-       RF230_RSSI_MASK = 0x1F,
-       RF230_CCA_REQUEST = 1 << 7,
-       RF230_CCA_MODE_0 = 0 << 5,
-       RF230_CCA_MODE_1 = 1 << 5,
-       RF230_CCA_MODE_2 = 2 << 5,
-       RF230_CCA_MODE_3 = 3 << 5,
-       RF230_CHANNEL_DEFAULT = 11,
-       RF230_CHANNEL_MASK = 0x1F,
-       RF230_CCA_CS_THRES_SHIFT = 4,
-       RF230_CCA_ED_THRES_SHIFT = 0,
-};
-
-enum rf230_irq_register_enums
-{
-       RF230_IRQ_BAT_LOW = 1 << 7,
-       RF230_IRQ_TRX_UR = 1 << 6,
-       RF230_IRQ_TRX_END = 1 << 3,
-       RF230_IRQ_RX_START = 1 << 2,
-       RF230_IRQ_PLL_UNLOCK = 1 << 1,
-       RF230_IRQ_PLL_LOCK = 1 << 0,
-};
-
-enum rf230_control_register_enums
-{
-       RF230_AVREG_EXT = 1 << 7,
-       RF230_AVDD_OK = 1 << 6,
-       RF230_DVREG_EXT = 1 << 3,
-       RF230_DVDD_OK = 1 << 2,
-       RF230_BATMON_OK = 1 << 5,
-       RF230_BATMON_VHR = 1 << 4,
-       RF230_BATMON_VTH_MASK = 0x0F,
-       RF230_XTAL_MODE_OFF = 0 << 4,
-       RF230_XTAL_MODE_EXTERNAL = 4 << 4,
-       RF230_XTAL_MODE_INTERNAL = 15 << 4,
-};
-
-enum rf230_pll_register_enums
-{
-       RF230_PLL_CF_START = 1 << 7,
-       RF230_PLL_DCU_START = 1 << 7,
-};
-
-enum rf230_spi_command_enums
-{
-       RF230_CMD_REGISTER_READ = 0x80,
-       RF230_CMD_REGISTER_WRITE = 0xC0,
-       RF230_CMD_REGISTER_MASK = 0x3F,
-       RF230_CMD_FRAME_READ = 0x20,
-       RF230_CMD_FRAME_WRITE = 0x60,
-       RF230_CMD_SRAM_READ = 0x00,
-       RF230_CMD_SRAM_WRITE = 0x40,
-};
-
-#endif//__RF230_H__
diff --git a/tos/chips/rf2xx/rf230/RF230ActiveMessage.h b/tos/chips/rf2xx/rf230/RF230ActiveMessage.h
new file mode 100644 (file)
index 0000000..e219b7c
--- /dev/null
@@ -0,0 +1,54 @@
+/*
+ * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
+ * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ * 
+ * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
+ * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+ *
+ * Author: Miklos Maroti
+ */
+
+#ifndef __RF230ACTIVEMESSAGE_H__
+#define __RF230ACTIVEMESSAGE_H__
+
+#include <IEEE154PacketLayer.h>
+#include <MetadataFlagsLayer.h>
+#include <RF230DriverLayer.h>
+#include <TimeStampingLayer.h>
+#include <LowPowerListeningLayer.h>
+#include <PacketLinkLayer.h>
+
+typedef ieee154_header_t rf230packet_header_t;
+
+typedef nx_struct rf230packet_footer_t
+{
+       // the time stamp is not recorded here, time stamped messaged cannot have max length
+} rf230packet_footer_t;
+
+typedef struct rf230packet_metadata_t
+{
+       flags_metadata_t flags;
+       rf230_metadata_t rf230;
+       timestamp_metadata_t timestamp;
+#ifdef LOW_POWER_LISTENING
+       lpl_metadata_t lpl;
+#endif
+#ifdef PACKET_LINK
+       link_metadata_t link;
+#endif
+} rf230packet_metadata_t;
+
+#endif//__RF230ACTIVEMESSAGE_H__
index af6e816e6441d6ce2a8e57919247f0b78baf3ce2..b11d0e2378b230f3a04256ad42170c5af5f79575 100644 (file)
@@ -36,8 +36,6 @@ configuration RF230ActiveMessageC
                interface Packet;
                interface AMPacket;
                interface PacketAcknowledgements;
-
-               // we provide a dummy LowPowerListening interface if LOW_POWER_LISTENING is not defined
                interface LowPowerListening;
 
 #ifdef PACKET_LINK
@@ -50,6 +48,7 @@ configuration RF230ActiveMessageC
                interface PacketField<uint8_t> as PacketTransmitPower;
                interface PacketField<uint8_t> as PacketRSSI;
 
+               interface LocalTime<TRadio> as LocalTimeRadio;
                interface PacketTimeStamp<TRadio, uint32_t> as PacketTimeStampRadio;
                interface PacketTimeStamp<TMilli, uint32_t> as PacketTimeStampMilli;
        }
@@ -57,112 +56,142 @@ configuration RF230ActiveMessageC
 
 implementation
 {
-       components RF230ActiveMessageP, RF230PacketC, IEEE154Packet2C, RadioAlarmC;
+       components RF230ActiveMessageP, IEEE154PacketLayerC, RadioAlarmC;
 
 #ifdef RADIO_DEBUG
        components AssertC;
 #endif
 
-       RF230ActiveMessageP.IEEE154Packet2 -> IEEE154Packet2C;
-       RF230ActiveMessageP.Packet -> RF230PacketC;
+       RF230ActiveMessageP.IEEE154PacketLayer -> IEEE154PacketLayerC;
        RF230ActiveMessageP.RadioAlarm -> RadioAlarmC.RadioAlarm[unique("RadioAlarm")];
+       RF230ActiveMessageP.PacketTimeStamp -> TimeStampingLayerC;
 
-       Packet = RF230PacketC;
-       AMPacket = RF230PacketC;
-       PacketAcknowledgements = RF230PacketC;
-       PacketLinkQuality = RF230PacketC.PacketLinkQuality;
-       PacketTransmitPower = RF230PacketC.PacketTransmitPower;
-       PacketRSSI = RF230PacketC.PacketRSSI;
-       PacketTimeStampRadio = RF230PacketC;
-       PacketTimeStampMilli = RF230PacketC;
-       LowPowerListening = LowPowerListeningLayerC;
-       RadioChannel = MessageBufferLayerC;
+       Packet = RF230ActiveMessageP;
+
+// -------- ActiveMessage
 
        components ActiveMessageLayerC;
+       ActiveMessageLayerC.Config -> RF230ActiveMessageP;
+       ActiveMessageLayerC.AMPacket -> IEEE154PacketLayerC;
+       ActiveMessageLayerC.SubSend -> IEEE154NetworkLayerC;
+       ActiveMessageLayerC.SubReceive -> IEEE154NetworkLayerC;
+       AMSend = ActiveMessageLayerC;
+       Receive = ActiveMessageLayerC.Receive;
+       Snoop = ActiveMessageLayerC.Snoop;
+       AMPacket = IEEE154PacketLayerC;
+
+// -------- IEEE154Network
+
 #ifdef TFRAMES_ENABLED
        components new DummyLayerC() as IEEE154NetworkLayerC;
 #else
        components IEEE154NetworkLayerC;
 #endif
+       IEEE154NetworkLayerC.SubSend -> UniqueLayerC;
+       IEEE154NetworkLayerC.SubReceive -> LowPowerListeningLayerC;
+
+// -------- UniqueLayer Send part (wired twice)
+
+       components UniqueLayerC;
+       UniqueLayerC.Config -> RF230ActiveMessageP;
+       UniqueLayerC.SubSend -> LowPowerListeningLayerC;
+
+// -------- Low Power Listening 
 
 #ifdef LOW_POWER_LISTENING
        components LowPowerListeningLayerC;
-       LowPowerListeningLayerC.PacketSleepInterval -> RF230PacketC;
-       LowPowerListeningLayerC.IEEE154Packet2 -> IEEE154Packet2C;
-       LowPowerListeningLayerC.PacketAcknowledgements -> RF230PacketC;
+       LowPowerListeningLayerC.PacketLplMetadata -> RF230ActiveMessageP;
+       LowPowerListeningLayerC.IEEE154PacketLayer -> IEEE154PacketLayerC;
+       LowPowerListeningLayerC.PacketAcknowledgements -> SoftwareAckLayerC;
 #else  
-       components new DummyLayerC() as LowPowerListeningLayerC;
+       components LowPowerListeningDummyC as LowPowerListeningLayerC;
 #endif
+       LowPowerListeningLayerC.SubControl -> MessageBufferLayerC;
+       LowPowerListeningLayerC.SubSend -> PacketLinkLayerC;
+       LowPowerListeningLayerC.SubReceive -> MessageBufferLayerC;
+       SplitControl = LowPowerListeningLayerC;
+       LowPowerListening = LowPowerListeningLayerC;
+
+// -------- Packet Link
 
 #ifdef PACKET_LINK
        components PacketLinkLayerC;
        PacketLink = PacketLinkLayerC;
-       PacketLinkLayerC.PacketData -> RF230PacketC;
-       PacketLinkLayerC.PacketAcknowledgements -> RF230PacketC;
+       PacketLinkLayerC.PacketLinkMetadata -> RF230ActiveMessageP;
+       PacketLinkLayerC.PacketAcknowledgements -> SoftwareAckLayerC;
 #else
        components new DummyLayerC() as PacketLinkLayerC;
 #endif
-
-       components MessageBufferLayerC;
-       components UniqueLayerC;
-       components TrafficMonitorLayerC;
-
-#ifdef SLOTTED_MAC
-       components SlottedCollisionLayerC as CollisionAvoidanceLayerC;
-#else
-       components RandomCollisionLayerC as CollisionAvoidanceLayerC;
-#endif
-
-       components SoftwareAckLayerC;
-       components new DummyLayerC() as CsmaLayerC;
-       components RF230DriverLayerC;
-
-       SplitControl = LowPowerListeningLayerC;
-       AMSend = ActiveMessageLayerC;
-       Receive = ActiveMessageLayerC.Receive;
-       Snoop = ActiveMessageLayerC.Snoop;
-
-       ActiveMessageLayerC.Config -> RF230ActiveMessageP;
-       ActiveMessageLayerC.AMPacket -> IEEE154Packet2C;
-       ActiveMessageLayerC.SubSend -> IEEE154NetworkLayerC;
-       ActiveMessageLayerC.SubReceive -> IEEE154NetworkLayerC;
-
-       IEEE154NetworkLayerC.SubSend -> UniqueLayerC;
-       IEEE154NetworkLayerC.SubReceive -> LowPowerListeningLayerC;
-
-       // the UniqueLayer is wired at two points
-       UniqueLayerC.Config -> RF230ActiveMessageP;
-       UniqueLayerC.SubSend -> LowPowerListeningLayerC;
-
-       LowPowerListeningLayerC.SubControl -> MessageBufferLayerC;
-       LowPowerListeningLayerC.SubSend -> PacketLinkLayerC;
-       LowPowerListeningLayerC.SubReceive -> MessageBufferLayerC;
-
        PacketLinkLayerC.SubSend -> MessageBufferLayerC;
 
-       MessageBufferLayerC.Packet -> RF230PacketC;
+// -------- MessageBuffer
+
+       components MessageBufferLayerC;
+       MessageBufferLayerC.Packet -> RF230ActiveMessageP;
        MessageBufferLayerC.RadioSend -> TrafficMonitorLayerC;
        MessageBufferLayerC.RadioReceive -> UniqueLayerC;
        MessageBufferLayerC.RadioState -> TrafficMonitorLayerC;
+       RadioChannel = MessageBufferLayerC;
+
+// -------- UniqueLayer receive part (wired twice)
 
        UniqueLayerC.SubReceive -> TrafficMonitorLayerC;
 
+// -------- Traffic Monitor
+
+       components TrafficMonitorLayerC;
        TrafficMonitorLayerC.Config -> RF230ActiveMessageP;
        TrafficMonitorLayerC.SubSend -> CollisionAvoidanceLayerC;
        TrafficMonitorLayerC.SubReceive -> CollisionAvoidanceLayerC;
        TrafficMonitorLayerC.SubState -> RF230DriverLayerC;
 
+// -------- CollisionAvoidance
+
+#ifdef SLOTTED_MAC
+       components SlottedCollisionLayerC as CollisionAvoidanceLayerC;
+#else
+       components RandomCollisionLayerC as CollisionAvoidanceLayerC;
+#endif
        CollisionAvoidanceLayerC.Config -> RF230ActiveMessageP;
        CollisionAvoidanceLayerC.SubSend -> SoftwareAckLayerC;
        CollisionAvoidanceLayerC.SubReceive -> SoftwareAckLayerC;
 
+// -------- SoftwareAcknowledgement
+
+       components SoftwareAckLayerC;
        SoftwareAckLayerC.Config -> RF230ActiveMessageP;
        SoftwareAckLayerC.SubSend -> CsmaLayerC;
        SoftwareAckLayerC.SubReceive -> RF230DriverLayerC;
+       PacketAcknowledgements = SoftwareAckLayerC;
+
+// -------- Carrier Sense
 
+       components new DummyLayerC() as CsmaLayerC;
        CsmaLayerC.Config -> RF230ActiveMessageP;
        CsmaLayerC -> RF230DriverLayerC.RadioSend;
        CsmaLayerC -> RF230DriverLayerC.RadioCCA;
 
+// -------- RF230 Driver
+
+       components RF230DriverLayerC;
+       RF230DriverLayerC.PacketRF230Metadata -> RF230ActiveMessageP;
        RF230DriverLayerC.RF230DriverConfig -> RF230ActiveMessageP;
+       RF230DriverLayerC.PacketTimeStamp -> TimeStampingLayerC;
+       PacketTransmitPower = RF230DriverLayerC.PacketTransmitPower;
+       PacketLinkQuality = RF230DriverLayerC.PacketLinkQuality;
+       PacketRSSI = RF230DriverLayerC.PacketRSSI;
+       LocalTimeRadio = RF230DriverLayerC;
+
+// -------- MetadataFlags
+
+       components MetadataFlagsLayerC;
+       MetadataFlagsLayerC.PacketFlagsMetadata -> RF230ActiveMessageP;
+
+// -------- TimeStamping
+
+       components TimeStampingLayerC;
+       TimeStampingLayerC.LocalTimeRadio -> RF230DriverLayerC;
+       TimeStampingLayerC.PacketTimeStampMetadata -> RF230ActiveMessageP;
+       PacketTimeStampRadio = TimeStampingLayerC;
+       PacketTimeStampMilli = TimeStampingLayerC;
 }
index 9c8044cd34a704c34e6e17c2a52c5956b01ffc5b..0842b5af1ae456795ebf0a75aa9c39d4cb87ff31 100644 (file)
@@ -21,7 +21,7 @@
  * Author: Miklos Maroti
  */
 
-#include <RF230Packet.h>
+#include <RF230ActiveMessage.h>
 #include <RadioConfig.h>
 #include <Tasklet.h>
 
@@ -38,13 +38,27 @@ module RF230ActiveMessageP
                interface SlottedCollisionConfig;
                interface ActiveMessageConfig;
                interface DummyConfig;
+
+               interface Packet;
+
+               interface PacketData<flags_metadata_t> as PacketFlagsMetadata;
+               interface PacketData<rf230_metadata_t> as PacketRF230Metadata;
+               interface PacketData<timestamp_metadata_t> as PacketTimeStampMetadata;
+
+#ifdef LOW_POWER_LISTENING
+               interface PacketData<lpl_metadata_t> as PacketLplMetadata;
+#endif
+#ifdef PACKET_LINK
+               interface PacketData<link_metadata_t> as PacketLinkMetadata;
+#endif
        }
 
        uses
        {
-               interface IEEE154Packet2;
-               interface Packet;
+               interface IEEE154PacketLayer;
                interface RadioAlarm;
+
+               interface PacketTimeStamp<TRadio, uint32_t>;
        }
 }
 
@@ -54,22 +68,17 @@ implementation
 
        async command uint8_t RF230DriverConfig.getLength(message_t* msg)
        {
-               return call IEEE154Packet2.getLength(msg);
+               return call IEEE154PacketLayer.getLength(msg);
        }
 
        async command void RF230DriverConfig.setLength(message_t* msg, uint8_t len)
        {
-               call IEEE154Packet2.setLength(msg, len);
+               call IEEE154PacketLayer.setLength(msg, len);
        }
 
        async command uint8_t* RF230DriverConfig.getPayload(message_t* msg)
        {
-               return ((uint8_t*)(call IEEE154Packet2.getHeader(msg))) + 1;
-       }
-
-       inline rf230packet_metadata_t* getMeta(message_t* msg)
-       {
-               return (rf230packet_metadata_t*)(msg->metadata);
+               return ((uint8_t*)(call IEEE154PacketLayer.getHeader(msg))) + 1;
        }
 
        async command uint8_t RF230DriverConfig.getHeaderLength()
@@ -86,42 +95,39 @@ implementation
 
        async command bool RF230DriverConfig.requiresRssiCca(message_t* msg)
        {
-               return call IEEE154Packet2.isDataFrame(msg);
+               return call IEEE154PacketLayer.isDataFrame(msg);
        }
 
 /*----------------- SoftwareAckConfig -----------------*/
 
        async command bool SoftwareAckConfig.requiresAckWait(message_t* msg)
        {
-               return call IEEE154Packet2.requiresAckWait(msg);
+               return call IEEE154PacketLayer.requiresAckWait(msg);
        }
 
        async command bool SoftwareAckConfig.isAckPacket(message_t* msg)
        {
-               return call IEEE154Packet2.isAckFrame(msg);
+               return call IEEE154PacketLayer.isAckFrame(msg);
        }
 
        async command bool SoftwareAckConfig.verifyAckPacket(message_t* data, message_t* ack)
        {
-               return call IEEE154Packet2.verifyAckReply(data, ack);
+               return call IEEE154PacketLayer.verifyAckReply(data, ack);
        }
 
-       async command bool SoftwareAckConfig.requiresAckReply(message_t* msg)
+       async command void SoftwareAckConfig.setAckRequired(message_t* msg, bool ack)
        {
-               return call IEEE154Packet2.requiresAckReply(msg);
+               call IEEE154PacketLayer.setAckRequired(msg, ack);
        }
 
-       async command void SoftwareAckConfig.createAckPacket(message_t* data, message_t* ack)
+       async command bool SoftwareAckConfig.requiresAckReply(message_t* msg)
        {
-               call IEEE154Packet2.createAckReply(data, ack);
+               return call IEEE154PacketLayer.requiresAckReply(msg);
        }
 
-       async command void SoftwareAckConfig.setAckReceived(message_t* msg, bool acked)
+       async command void SoftwareAckConfig.createAckPacket(message_t* data, message_t* ack)
        {
-               if( acked )
-                       getMeta(msg)->flags |= RF230PACKET_WAS_ACKED;
-               else
-                       getMeta(msg)->flags &= ~RF230PACKET_WAS_ACKED;
+               call IEEE154PacketLayer.createAckReply(data, ack);
        }
 
        async command uint16_t SoftwareAckConfig.getAckTimeout()
@@ -138,17 +144,17 @@ implementation
 
        async command uint8_t UniqueConfig.getSequenceNumber(message_t* msg)
        {
-               return call IEEE154Packet2.getDSN(msg);
+               return call IEEE154PacketLayer.getDSN(msg);
        }
 
        async command void UniqueConfig.setSequenceNumber(message_t* msg, uint8_t dsn)
        {
-               call IEEE154Packet2.setDSN(msg, dsn);
+               call IEEE154PacketLayer.setDSN(msg, dsn);
        }
 
        async command am_addr_t UniqueConfig.getSender(message_t* msg)
        {
-               return call IEEE154Packet2.getSrcAddr(msg);
+               return call IEEE154PacketLayer.getSrcAddr(msg);
        }
 
        tasklet_async command void UniqueConfig.reportChannelError()
@@ -161,7 +167,7 @@ implementation
        command error_t ActiveMessageConfig.checkPacket(message_t* msg)
        {
                // the user forgot to call clear, we should return EINVAL
-               if( ! call IEEE154Packet2.isDataFrame(msg) )
+               if( ! call IEEE154PacketLayer.isDataFrame(msg) )
                        call Packet.clear(msg);
 
                return SUCCESS;
@@ -171,7 +177,7 @@ implementation
 
        async command bool CsmaConfig.requiresSoftwareCCA(message_t* msg)
        {
-               return call IEEE154Packet2.isDataFrame(msg);
+               return call IEEE154PacketLayer.isDataFrame(msg);
        }
 
 /*----------------- TrafficMonitorConfig -----------------*/
@@ -196,13 +202,13 @@ implementation
                 * ack required: 8-16 byte separation, 11 bytes airtime, 5-10 bytes separation
                 */
 
-               uint8_t len = call IEEE154Packet2.getLength(msg);
-               return call IEEE154Packet2.getAckRequired(msg) ? len + 6 + 16 + 11 + 10 : len + 6 + 10;
+               uint8_t len = call IEEE154PacketLayer.getLength(msg);
+               return call IEEE154PacketLayer.getAckRequired(msg) ? len + 6 + 16 + 11 + 10 : len + 6 + 10;
        }
 
        async command am_addr_t TrafficMonitorConfig.getSender(message_t* msg)
        {
-               return call IEEE154Packet2.getSrcAddr(msg);
+               return call IEEE154PacketLayer.getSrcAddr(msg);
        }
 
        tasklet_async command void TrafficMonitorConfig.timerTick()
@@ -244,7 +250,7 @@ implementation
                time = call RadioAlarm.getNow();
 
                // estimated response time (download the message, etc) is 5-8 bytes
-               if( call IEEE154Packet2.requiresAckReply(msg) )
+               if( call IEEE154PacketLayer.requiresAckReply(msg) )
                        time += (uint16_t)(32 * (-5 + 16 + 11 + 5) * RADIO_ALARM_MICROSEC);
                else
                        time += (uint16_t)(32 * (-5 + 5) * RADIO_ALARM_MICROSEC);
@@ -269,13 +275,13 @@ implementation
        async command uint16_t SlottedCollisionConfig.getTransmitTime(message_t* msg)
        {
                // TODO: check if the timestamp is correct
-               return getMeta(msg)->timestamp;
+               return call PacketTimeStamp.timestamp(msg);
        }
 
        async command uint16_t SlottedCollisionConfig.getCollisionWindowStart(message_t* msg)
        {
                // the preamble (4 bytes), SFD (1 byte), plus two extra for safety
-               return getMeta(msg)->timestamp - (uint16_t)(7 * 32 * RADIO_ALARM_MICROSEC);
+               return (call PacketTimeStamp.timestamp(msg)) - (uint16_t)(7 * 32 * RADIO_ALARM_MICROSEC);
        }
 
        async command uint16_t SlottedCollisionConfig.getCollisionWindowLength(message_t* msg)
@@ -290,4 +296,86 @@ implementation
        async command void DummyConfig.nothing()
        {
        }
+
+/*----------------- Metadata -----------------*/
+
+       inline rf230packet_metadata_t* getMeta(message_t* msg)
+       {
+               return (rf230packet_metadata_t*)(msg->metadata);
+       }
+
+       async command flags_metadata_t* PacketFlagsMetadata.get(message_t* msg)
+       {
+               return &(getMeta(msg)->flags);
+       }
+
+       async command rf230_metadata_t* PacketRF230Metadata.get(message_t* msg)
+       {
+               return &(getMeta(msg)->rf230);
+       }
+
+       async command timestamp_metadata_t* PacketTimeStampMetadata.get(message_t* msg)
+       {
+               return &(getMeta(msg)->timestamp);
+       }
+
+#ifdef LOW_POWER_LISTENING
+       async command lpl_metadata_t* PacketLplMetadata.get(message_t* msg)
+       {
+               return &(getMeta(msg)->lpl);
+       }
+#endif
+
+#ifdef PACKET_LINK
+       async command link_metadata_t* PacketLinkMetadata.get(message_t* msg)
+       {
+               return &(getMeta(msg)->link);
+       }
+#endif
+
+/*----------------- Packet -----------------*/
+
+       enum
+       {
+               PACKET_LENGTH_INCREASE =
+                       sizeof(rf230packet_header_t) - 1        // the 8-bit length field is not counted
+                       + sizeof(ieee154_footer_t),             // the CRC is not stored in memory
+       };
+
+       command void Packet.clear(message_t* msg)
+       {
+               signal PacketFlagsMetadata.clear(msg);
+               signal PacketRF230Metadata.clear(msg);
+               signal PacketTimeStampMetadata.clear(msg);
+#ifdef LOW_POWER_LISTENING
+               signal PacketLplMetadata.clear(msg);
+#endif
+#ifdef PACKET_LINK
+               signal PacketLinkMetadata.clear(msg);
+#endif
+               call IEEE154PacketLayer.createDataFrame(msg);
+       }
+
+       inline command void Packet.setPayloadLength(message_t* msg, uint8_t len)
+       {
+               call IEEE154PacketLayer.setLength(msg, len + PACKET_LENGTH_INCREASE);
+       }
+
+       inline command uint8_t Packet.payloadLength(message_t* msg)
+       {
+               return call IEEE154PacketLayer.getLength(msg) - PACKET_LENGTH_INCREASE;
+       }
+
+       inline command uint8_t Packet.maxPayloadLength()
+       {
+               return TOSH_DATA_LENGTH;
+       }
+
+       command void* Packet.getPayload(message_t* msg, uint8_t len)
+       {
+               if( len > TOSH_DATA_LENGTH )
+                       return NULL;
+
+               return msg->data;
+       }
 }
diff --git a/tos/chips/rf2xx/rf230/RF230DriverLayer.h b/tos/chips/rf2xx/rf230/RF230DriverLayer.h
new file mode 100644 (file)
index 0000000..c57969f
--- /dev/null
@@ -0,0 +1,162 @@
+/*
+ * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
+ * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ * 
+ * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
+ * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+ *
+ * Author: Miklos Maroti
+ */
+
+#ifndef __RF230DRIVERLAYER_H__
+#define __RF230DRIVERLAYER_H__
+
+typedef struct rf230_metadata_t
+{
+       uint8_t lqi;
+       union
+       {
+               uint8_t power;
+               uint8_t rssi;
+       };
+} rf230_metadata_t;
+
+enum rf230_registers_enum
+{
+       RF230_TRX_STATUS = 0x01,
+       RF230_TRX_STATE = 0x02,
+       RF230_TRX_CTRL_0 = 0x03,
+       RF230_PHY_TX_PWR = 0x05,
+       RF230_PHY_RSSI = 0x06,
+       RF230_PHY_ED_LEVEL = 0x07,
+       RF230_PHY_CC_CCA = 0x08,
+       RF230_CCA_THRES = 0x09,
+       RF230_IRQ_MASK = 0x0E,
+       RF230_IRQ_STATUS = 0x0F,
+       RF230_VREG_CTRL = 0x10,
+       RF230_BATMON = 0x11,
+       RF230_XOSC_CTRL = 0x12,
+       RF230_PLL_CF = 0x1A,
+       RF230_PLL_DCU = 0x1B,
+       RF230_PART_NUM = 0x1C,
+       RF230_VERSION_NUM = 0x1D,
+       RF230_MAN_ID_0 = 0x1E,
+       RF230_MAN_ID_1 = 0x1F,
+       RF230_SHORT_ADDR_0 = 0x20,
+       RF230_SHORT_ADDR_1 = 0x21,
+       RF230_PAN_ID_0 = 0x22,
+       RF230_PAN_ID_1 = 0x23,
+       RF230_IEEE_ADDR_0 = 0x24,
+       RF230_IEEE_ADDR_1 = 0x25,
+       RF230_IEEE_ADDR_2 = 0x26,
+       RF230_IEEE_ADDR_3 = 0x27,
+       RF230_IEEE_ADDR_4 = 0x28,
+       RF230_IEEE_ADDR_5 = 0x29,
+       RF230_IEEE_ADDR_6 = 0x2A,
+       RF230_IEEE_ADDR_7 = 0x2B,
+       RF230_XAH_CTRL = 0x2C,
+       RF230_CSMA_SEED_0 = 0x2D,
+       RF230_CSMA_SEED_1 = 0x2E,
+};
+
+enum rf230_trx_register_enums
+{
+       RF230_CCA_DONE = 1 << 7,
+       RF230_CCA_STATUS = 1 << 6,
+       RF230_TRX_STATUS_MASK = 0x1F,
+       RF230_P_ON = 0,
+       RF230_BUSY_RX = 1,
+       RF230_BUSY_TX = 2,
+       RF230_RX_ON = 6,
+       RF230_TRX_OFF = 8,
+       RF230_PLL_ON = 9,
+       RF230_SLEEP = 15,
+       RF230_BUSY_RX_AACK = 16,
+       RF230_BUSR_TX_ARET = 17,
+       RF230_RX_AACK_ON = 22,
+       RF230_TX_ARET_ON = 25,
+       RF230_RX_ON_NOCLK = 28,
+       RF230_AACK_ON_NOCLK = 29,
+       RF230_BUSY_RX_AACK_NOCLK = 30,
+       RF230_STATE_TRANSITION_IN_PROGRESS = 31,
+       RF230_TRAC_STATUS_MASK = 0xE0,
+       RF230_TRAC_SUCCESS = 0,
+       RF230_TRAC_CHANNEL_ACCESS_FAILURE = 3 << 5,
+       RF230_TRAC_NO_ACK = 5 << 5,
+       RF230_TRX_CMD_MASK = 0x1F,
+       RF230_NOP = 0,
+       RF230_TX_START = 2,
+       RF230_FORCE_TRX_OFF = 3,
+};
+
+enum rf230_phy_register_enums
+{
+       RF230_TX_AUTO_CRC_ON = 1 << 7,
+       RF230_TX_PWR_MASK = 0x0F,
+       RF230_RSSI_MASK = 0x1F,
+       RF230_CCA_REQUEST = 1 << 7,
+       RF230_CCA_MODE_0 = 0 << 5,
+       RF230_CCA_MODE_1 = 1 << 5,
+       RF230_CCA_MODE_2 = 2 << 5,
+       RF230_CCA_MODE_3 = 3 << 5,
+       RF230_CHANNEL_DEFAULT = 11,
+       RF230_CHANNEL_MASK = 0x1F,
+       RF230_CCA_CS_THRES_SHIFT = 4,
+       RF230_CCA_ED_THRES_SHIFT = 0,
+};
+
+enum rf230_irq_register_enums
+{
+       RF230_IRQ_BAT_LOW = 1 << 7,
+       RF230_IRQ_TRX_UR = 1 << 6,
+       RF230_IRQ_TRX_END = 1 << 3,
+       RF230_IRQ_RX_START = 1 << 2,
+       RF230_IRQ_PLL_UNLOCK = 1 << 1,
+       RF230_IRQ_PLL_LOCK = 1 << 0,
+};
+
+enum rf230_control_register_enums
+{
+       RF230_AVREG_EXT = 1 << 7,
+       RF230_AVDD_OK = 1 << 6,
+       RF230_DVREG_EXT = 1 << 3,
+       RF230_DVDD_OK = 1 << 2,
+       RF230_BATMON_OK = 1 << 5,
+       RF230_BATMON_VHR = 1 << 4,
+       RF230_BATMON_VTH_MASK = 0x0F,
+       RF230_XTAL_MODE_OFF = 0 << 4,
+       RF230_XTAL_MODE_EXTERNAL = 4 << 4,
+       RF230_XTAL_MODE_INTERNAL = 15 << 4,
+};
+
+enum rf230_pll_register_enums
+{
+       RF230_PLL_CF_START = 1 << 7,
+       RF230_PLL_DCU_START = 1 << 7,
+};
+
+enum rf230_spi_command_enums
+{
+       RF230_CMD_REGISTER_READ = 0x80,
+       RF230_CMD_REGISTER_WRITE = 0xC0,
+       RF230_CMD_REGISTER_MASK = 0x3F,
+       RF230_CMD_FRAME_READ = 0x20,
+       RF230_CMD_FRAME_WRITE = 0x60,
+       RF230_CMD_SRAM_READ = 0x00,
+       RF230_CMD_SRAM_WRITE = 0x40,
+};
+
+#endif//__RF230DRIVERLAYER_H__
index 021e0982fc45d72f167b18a15df50e9e7ae5dcb2..8b58211df26dcfae8fc19e0daeca0593e04d8808 100644 (file)
@@ -21,6 +21,9 @@
  * Author: Miklos Maroti
  */
 
+#include <RadioConfig.h>
+#include <RF230DriverLayer.h>
+
 configuration RF230DriverLayerC
 {
        provides
@@ -29,28 +32,53 @@ configuration RF230DriverLayerC
                interface RadioSend;
                interface RadioReceive;
                interface RadioCCA;
+
+               interface PacketField<uint8_t> as PacketTransmitPower;
+               interface PacketField<uint8_t> as PacketRSSI;
+               interface PacketField<uint8_t> as PacketTimeSyncOffset;
+               interface PacketField<uint8_t> as PacketLinkQuality;
+
+               interface LocalTime<TRadio> as LocalTimeRadio;
        }
 
-       uses interface RF230DriverConfig;
+       uses
+       {
+               interface RF230DriverConfig;
+               interface PacketTimeStamp<TRadio, uint32_t>;
+               interface PacketData<rf230_metadata_t> as PacketRF230Metadata;
+       }
 }
 
 implementation
 {
-       components RF230DriverLayerP, HplRF230C, BusyWaitMicroC, TaskletC, MainC, RadioAlarmC, RF230PacketC, LocalTimeMicroC as LocalTimeRadioC;
+       components RF230DriverLayerP, HplRF230C, BusyWaitMicroC, TaskletC, MainC, RadioAlarmC;
 
        RadioState = RF230DriverLayerP;
        RadioSend = RF230DriverLayerP;
        RadioReceive = RF230DriverLayerP;
        RadioCCA = RF230DriverLayerP;
 
+       LocalTimeRadio = HplRF230C;
+
        RF230DriverConfig = RF230DriverLayerP;
+       PacketRF230Metadata = RF230DriverLayerP;
+
+       PacketTransmitPower = RF230DriverLayerP.PacketTransmitPower;
+       components new MetadataFlagC() as TransmitPowerFlagC;
+       RF230DriverLayerP.TransmitPowerFlag -> TransmitPowerFlagC;
+
+       PacketRSSI = RF230DriverLayerP.PacketRSSI;
+       components new MetadataFlagC() as RSSIFlagC;
+       RF230DriverLayerP.RSSIFlag -> RSSIFlagC;
+
+       PacketTimeSyncOffset = RF230DriverLayerP.PacketTimeSyncOffset;
+       components new MetadataFlagC() as TimeSyncFlagC;
+       RF230DriverLayerP.TimeSyncFlag -> TimeSyncFlagC;
+
+       PacketLinkQuality = RF230DriverLayerP.PacketLinkQuality;
+       PacketTimeStamp = RF230DriverLayerP.PacketTimeStamp;
 
-       RF230DriverLayerP.PacketLinkQuality -> RF230PacketC.PacketLinkQuality;
-       RF230DriverLayerP.PacketTransmitPower -> RF230PacketC.PacketTransmitPower;
-       RF230DriverLayerP.PacketRSSI -> RF230PacketC.PacketRSSI;
-       RF230DriverLayerP.PacketTimeSyncOffset -> RF230PacketC.PacketTimeSyncOffset;
-       RF230DriverLayerP.PacketTimeStamp -> RF230PacketC;
-       RF230DriverLayerP.LocalTime -> LocalTimeRadioC;
+       RF230DriverLayerP.LocalTime -> HplRF230C;
 
        RF230DriverLayerP.RadioAlarm -> RadioAlarmC.RadioAlarm[unique("RadioAlarm")];
        RadioAlarmC.Alarm -> HplRF230C.Alarm;
index 17ea8ffa13a7be06272d0eb33272000c7f184061..77e94ad24a65c3a5bb7c4796b0c272bceeb8e2a1 100644 (file)
@@ -21,7 +21,7 @@
  * Author: Miklos Maroti
  */
 
-#include <RF230.h>
+#include <RF230DriverLayer.h>
 #include <Tasklet.h>
 #include <RadioAssert.h>
 #include <GenericTimeSyncMessage.h>
@@ -38,6 +38,11 @@ module RF230DriverLayerP
                interface RadioSend;
                interface RadioReceive;
                interface RadioCCA;
+
+               interface PacketField<uint8_t> as PacketTransmitPower;
+               interface PacketField<uint8_t> as PacketRSSI;
+               interface PacketField<uint8_t> as PacketTimeSyncOffset;
+               interface PacketField<uint8_t> as PacketLinkQuality;
        }
 
        uses
@@ -53,16 +58,17 @@ module RF230DriverLayerP
                interface GpioCapture as IRQ;
 
                interface BusyWait<TMicro, uint16_t>;
+               interface LocalTime<TRadio>;
 
-               interface PacketField<uint8_t> as PacketLinkQuality;
-               interface PacketField<uint8_t> as PacketTransmitPower;
-               interface PacketField<uint8_t> as PacketRSSI;
-               interface PacketField<uint8_t> as PacketTimeSyncOffset;
+               interface RF230DriverConfig;
+
+               interface PacketData<rf230_metadata_t> as PacketRF230Metadata;
+               interface PacketFlag as TransmitPowerFlag;
+               interface PacketFlag as RSSIFlag;
+               interface PacketFlag as TimeSyncFlag;
 
                interface PacketTimeStamp<TRadio, uint32_t>;
-               interface LocalTime<TRadio>;
 
-               interface RF230DriverConfig;
                interface Tasklet;
                interface RadioAlarm;
 
@@ -829,4 +835,112 @@ implementation
                if( cmd == CMD_NONE )
                        call SpiResource.release();
        }
+
+/*----------------- PACKET -----------------*/
+
+       async event void PacketRF230Metadata.clear(message_t* msg)
+       {
+       }
+
+// --- TransmitPower
+
+       async command bool PacketTransmitPower.isSet(message_t* msg)
+       {
+               return call TransmitPowerFlag.get(msg);
+       }
+
+       async command uint8_t PacketTransmitPower.get(message_t* msg)
+       {
+               return (call PacketRF230Metadata.get(msg))->power;
+       }
+
+       async command void PacketTransmitPower.clear(message_t* msg)
+       {
+               call TransmitPowerFlag.clear(msg);
+       }
+
+       async command void PacketTransmitPower.set(message_t* msg, uint8_t value)
+       {
+               call TransmitPowerFlag.set(msg);
+               (call PacketRF230Metadata.get(msg))->power = value;
+       }
+
+// --- RSSI
+
+       async command bool PacketRSSI.isSet(message_t* msg)
+       {
+               return call RSSIFlag.get(msg);
+       }
+
+       async command uint8_t PacketRSSI.get(message_t* msg)
+       {
+               return (call PacketRF230Metadata.get(msg))->rssi;
+       }
+
+       async command void PacketRSSI.clear(message_t* msg)
+       {
+               call RSSIFlag.clear(msg);
+       }
+
+       async command void PacketRSSI.set(message_t* msg, uint8_t value)
+       {
+               // just to be safe if the user fails to clear the packet
+               call TransmitPowerFlag.clear(msg);
+
+               call RSSIFlag.set(msg);
+               (call PacketRF230Metadata.get(msg))->rssi = value;
+       }
+
+// --- TimeSyncOffset
+
+       enum
+       {
+               PACKET_LENGTH_INCREASE =
+                       sizeof(rf230packet_header_t) - 1        // the 8-bit length field is not counted
+                       + sizeof(ieee154_footer_t),             // the CRC is not stored in memory
+       };
+
+       async command bool PacketTimeSyncOffset.isSet(message_t* msg)
+       {
+               return call TimeSyncFlag.get(msg);
+       }
+
+       async command uint8_t PacketTimeSyncOffset.get(message_t* msg)
+       {
+               return call RF230DriverConfig.getLength(msg) - PACKET_LENGTH_INCREASE - sizeof(timesync_absolute_t);
+       }
+
+       async command void PacketTimeSyncOffset.clear(message_t* msg)
+       {
+               call TimeSyncFlag.clear(msg);
+       }
+
+       async command void PacketTimeSyncOffset.set(message_t* msg, uint8_t value)
+       {
+               // we do not store the value, the time sync field is always the last 4 bytes
+               ASSERT( call RF230DriverConfig.getLength(msg) - PACKET_LENGTH_INCREASE - sizeof(timesync_absolute_t) == value );
+
+               call TimeSyncFlag.set(msg);
+       }
+
+// --- LinkQuality
+
+       async command bool PacketLinkQuality.isSet(message_t* msg)
+       {
+               return TRUE;
+       }
+
+       async command uint8_t PacketLinkQuality.get(message_t* msg)
+       {
+               return (call PacketRF230Metadata.get(msg))->lqi;
+       }
+
+       async command void PacketLinkQuality.clear(message_t* msg)
+       {
+       }
+
+       async command void PacketLinkQuality.set(message_t* msg, uint8_t value)
+       {
+               (call PacketRF230Metadata.get(msg))->lqi = value;
+       }
 }
diff --git a/tos/chips/rf2xx/rf230/RF230Packet.h b/tos/chips/rf2xx/rf230/RF230Packet.h
deleted file mode 100644 (file)
index 802aa51..0000000
+++ /dev/null
@@ -1,63 +0,0 @@
-/*
- * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
- * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
- * 
- * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
- * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
- *
- * Author: Miklos Maroti
- */
-
-#ifndef __RF230PACKET_H__
-#define __RF230PACKET_H__
-
-#include <IEEE154Packet2.h>
-#include <PacketLinkLayer.h>
-
-typedef ieee154_header_t rf230packet_header_t;
-
-typedef nx_struct rf230packet_footer_t
-{
-       // the time stamp is not recorded here, time stamped messaged cannot have max length
-} rf230packet_footer_t;
-
-typedef struct rf230packet_metadata_t
-{
-       uint8_t flags;
-       uint8_t lqi;
-       uint8_t power;                          // shared between TXPOWER and RSSI
-#ifdef LOW_POWER_LISTENING
-       uint16_t lpl_sleepint;
-#endif
-#ifdef PACKET_LINK
-       packet_link_metadata_t packet_link;
-#endif
-       uint32_t timestamp;
-} rf230packet_metadata_t;
-
-enum rf230packet_metadata_flags
-{
-       RF230PACKET_WAS_ACKED = 0x01,           // PacketAcknowledgements
-       RF230PACKET_TIMESTAMP = 0x02,           // PacketTimeStamp
-       RF230PACKET_TXPOWER = 0x04,             // PacketTransmitPower
-       RF230PACKET_RSSI = 0x08,                // PacketRSSI
-       RF230PACKET_TIMESYNC = 0x10,            // PacketTimeSync (update timesync_footer)
-       RF230PACKET_LPL_SLEEPINT = 0x20,        // LowPowerListening
-
-       RF230PACKET_CLEAR_METADATA = 0x00,
-};
-
-#endif//__RF230PACKET_H__
diff --git a/tos/chips/rf2xx/rf230/RF230PacketC.nc b/tos/chips/rf2xx/rf230/RF230PacketC.nc
deleted file mode 100644 (file)
index 31e8269..0000000
+++ /dev/null
@@ -1,69 +0,0 @@
-/*
- * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
- * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
- * 
- * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
- * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
- *
- * Author: Miklos Maroti
- */
-
-configuration RF230PacketC
-{
-       provides
-       {
-               interface Packet;
-               interface AMPacket;
-               interface PacketAcknowledgements;
-               interface PacketField<uint8_t> as PacketLinkQuality;
-               interface PacketField<uint8_t> as PacketTransmitPower;
-               interface PacketField<uint8_t> as PacketRSSI;
-               interface PacketField<uint16_t> as PacketSleepInterval;
-               interface PacketField<uint8_t> as PacketTimeSyncOffset;
-
-               interface PacketTimeStamp<TRadio, uint32_t> as PacketTimeStampRadio;
-               interface PacketTimeStamp<TMilli, uint32_t> as PacketTimeStampMilli;
-#ifdef PACKET_LINK
-               interface PacketData<packet_link_metadata_t> as PaketLinkMetadata;
-#endif
-       }
-}
-
-implementation
-{
-       components RF230PacketP, IEEE154Packet2C, LocalTimeMicroC, LocalTimeMilliC;
-
-       RF230PacketP.IEEE154Packet2 -> IEEE154Packet2C;
-       RF230PacketP.LocalTimeRadio -> LocalTimeMicroC;
-       RF230PacketP.LocalTimeMilli -> LocalTimeMilliC;
-
-       Packet = RF230PacketP;
-       AMPacket = IEEE154Packet2C;
-
-       PacketAcknowledgements  = RF230PacketP;
-       PacketLinkQuality       = RF230PacketP.PacketLinkQuality;
-       PacketTransmitPower     = RF230PacketP.PacketTransmitPower;
-       PacketRSSI              = RF230PacketP.PacketRSSI;
-       PacketSleepInterval     = RF230PacketP.PacketSleepInterval;
-       PacketTimeSyncOffset    = RF230PacketP.PacketTimeSyncOffset;
-
-       PacketTimeStampRadio    = RF230PacketP;
-       PacketTimeStampMilli    = RF230PacketP;
-
-#ifdef PACKET_LINK
-       PaketLinkMetadata       = RF230PacketP;
-#endif
-}
diff --git a/tos/chips/rf2xx/rf230/RF230PacketP.nc b/tos/chips/rf2xx/rf230/RF230PacketP.nc
deleted file mode 100644 (file)
index de875b0..0000000
+++ /dev/null
@@ -1,305 +0,0 @@
-/*
- * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
- * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
- *
- * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
- * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
- *
- * Author: Miklos Maroti
- */
-
-#include <RF230Packet.h>
-#include <GenericTimeSyncMessage.h>
-#include <RadioConfig.h>
-#include <PacketLinkLayer.h>
-
-module RF230PacketP
-{
-       provides
-       {
-               interface PacketAcknowledgements;
-               interface Packet;
-               interface PacketField<uint8_t> as PacketLinkQuality;
-               interface PacketField<uint8_t> as PacketTransmitPower;
-               interface PacketField<uint8_t> as PacketRSSI;
-               interface PacketField<uint16_t> as PacketSleepInterval;
-               interface PacketField<uint8_t> as PacketTimeSyncOffset;
-
-               interface PacketTimeStamp<TRadio, uint32_t> as PacketTimeStampRadio;
-               interface PacketTimeStamp<TMilli, uint32_t> as PacketTimeStampMilli;
-
-#ifdef PACKET_LINK
-               interface PacketData<packet_link_metadata_t> as PacketLinkMetadata;
-#endif
-       }
-
-       uses
-       {
-               interface IEEE154Packet2;
-
-               interface LocalTime<TRadio> as LocalTimeRadio;
-               interface LocalTime<TMilli> as LocalTimeMilli;
-       }
-}
-
-implementation
-{
-       enum
-       {
-               PACKET_LENGTH_INCREASE =
-                       sizeof(rf230packet_header_t) - 1        // the 8-bit length field is not counted
-                       + sizeof(ieee154_footer_t),             // the CRC is not stored in memory
-       };
-
-       inline rf230packet_metadata_t* getMeta(message_t* msg)
-       {
-               return (rf230packet_metadata_t*)(msg->metadata);
-       }
-
-/*----------------- Packet -----------------*/
-
-       command void Packet.clear(message_t* msg)
-       {
-               call IEEE154Packet2.createDataFrame(msg);
-
-               getMeta(msg)->flags = RF230PACKET_CLEAR_METADATA;
-       }
-
-       inline command void Packet.setPayloadLength(message_t* msg, uint8_t len)
-       {
-               call IEEE154Packet2.setLength(msg, len + PACKET_LENGTH_INCREASE);
-       }
-
-       inline command uint8_t Packet.payloadLength(message_t* msg)
-       {
-               return call IEEE154Packet2.getLength(msg) - PACKET_LENGTH_INCREASE;
-       }
-
-       inline command uint8_t Packet.maxPayloadLength()
-       {
-               return TOSH_DATA_LENGTH;
-       }
-
-       command void* Packet.getPayload(message_t* msg, uint8_t len)
-       {
-               if( len > TOSH_DATA_LENGTH )
-                       return NULL;
-
-               return msg->data;
-       }
-
-/*----------------- PacketAcknowledgements -----------------*/
-
-       async command error_t PacketAcknowledgements.requestAck(message_t* msg)
-       {
-               call IEEE154Packet2.setAckRequired(msg, TRUE);
-
-               return SUCCESS;
-       }
-
-       async command error_t PacketAcknowledgements.noAck(message_t* msg)
-       {
-               call IEEE154Packet2.setAckRequired(msg, FALSE);
-
-               return SUCCESS;
-       }
-
-       async command bool PacketAcknowledgements.wasAcked(message_t* msg)
-       {
-               return getMeta(msg)->flags & RF230PACKET_WAS_ACKED;
-       }
-
-/*----------------- PacketLinkQuality -----------------*/
-
-       async command bool PacketLinkQuality.isSet(message_t* msg)
-       {
-               return TRUE;
-       }
-
-       async command uint8_t PacketLinkQuality.get(message_t* msg)
-       {
-               return getMeta(msg)->lqi;
-       }
-
-       async command void PacketLinkQuality.clear(message_t* msg)
-       {
-       }
-
-       async command void PacketLinkQuality.set(message_t* msg, uint8_t value)
-       {
-               getMeta(msg)->lqi = value;
-       }
-
-/*----------------- PacketTimeStampRadio -----------------*/
-
-       async command bool PacketTimeStampRadio.isValid(message_t* msg)
-       {
-               return getMeta(msg)->flags & RF230PACKET_TIMESTAMP;
-       }
-
-       async command uint32_t PacketTimeStampRadio.timestamp(message_t* msg)
-       {
-               return getMeta(msg)->timestamp;
-       }
-
-       async command void PacketTimeStampRadio.clear(message_t* msg)
-       {
-               getMeta(msg)->flags &= ~RF230PACKET_TIMESTAMP;
-       }
-
-       async command void PacketTimeStampRadio.set(message_t* msg, uint32_t value)
-       {
-               getMeta(msg)->flags |= RF230PACKET_TIMESTAMP;
-               getMeta(msg)->timestamp = value;
-       }
-
-/*----------------- PacketTimeStampMilli -----------------*/
-
-       async command bool PacketTimeStampMilli.isValid(message_t* msg)
-       {
-               return call PacketTimeStampRadio.isValid(msg);
-       }
-
-       async command uint32_t PacketTimeStampMilli.timestamp(message_t* msg)
-       {
-               int32_t offset = call PacketTimeStampRadio.timestamp(msg) - call LocalTimeRadio.get();
-
-               return (offset >> RADIO_ALARM_MILLI_EXP) + call LocalTimeMilli.get();
-       }
-
-       async command void PacketTimeStampMilli.clear(message_t* msg)
-       {
-               call PacketTimeStampRadio.clear(msg);
-       }
-
-       async command void PacketTimeStampMilli.set(message_t* msg, uint32_t value)
-       {
-               int32_t offset = (value - call LocalTimeMilli.get()) << RADIO_ALARM_MILLI_EXP;
-
-               call PacketTimeStampRadio.set(msg, offset + call LocalTimeRadio.get());
-       }
-
-/*----------------- PacketTransmitPower -----------------*/
-
-       async command bool PacketTransmitPower.isSet(message_t* msg)
-       {
-               return getMeta(msg)->flags & RF230PACKET_TXPOWER;
-       }
-
-       async command uint8_t PacketTransmitPower.get(message_t* msg)
-       {
-               return getMeta(msg)->power;
-       }
-
-       async command void PacketTransmitPower.clear(message_t* msg)
-       {
-               getMeta(msg)->flags &= ~RF230PACKET_TXPOWER;
-       }
-
-       async command void PacketTransmitPower.set(message_t* msg, uint8_t value)
-       {
-               getMeta(msg)->flags &= ~RF230PACKET_RSSI;
-               getMeta(msg)->flags |= RF230PACKET_TXPOWER;
-               getMeta(msg)->power = value;
-       }
-
-/*----------------- PacketRSSI -----------------*/
-
-       async command bool PacketRSSI.isSet(message_t* msg)
-       {
-               return getMeta(msg)->flags & RF230PACKET_RSSI;
-       }
-
-       async command uint8_t PacketRSSI.get(message_t* msg)
-       {
-               return getMeta(msg)->power;
-       }
-
-       async command void PacketRSSI.clear(message_t* msg)
-       {
-               getMeta(msg)->flags &= ~RF230PACKET_RSSI;
-       }
-
-       async command void PacketRSSI.set(message_t* msg, uint8_t value)
-       {
-               getMeta(msg)->flags &= ~RF230PACKET_TXPOWER;
-               getMeta(msg)->flags |= RF230PACKET_RSSI;
-               getMeta(msg)->power = value;
-       }
-
-/*----------------- PacketTimeSyncOffset -----------------*/
-
-       async command bool PacketTimeSyncOffset.isSet(message_t* msg)
-       {
-               return getMeta(msg)->flags & RF230PACKET_TIMESYNC;
-       }
-
-       async command uint8_t PacketTimeSyncOffset.get(message_t* msg)
-       {
-               return call IEEE154Packet2.getLength(msg) - PACKET_LENGTH_INCREASE - sizeof(timesync_absolute_t);
-       }
-
-       async command void PacketTimeSyncOffset.clear(message_t* msg)
-       {
-               getMeta(msg)->flags &= ~RF230PACKET_TIMESYNC;
-       }
-
-       async command void PacketTimeSyncOffset.set(message_t* msg, uint8_t value)
-       {
-               // the value is ignored, the offset always points to the timesync footer at the end of the payload
-               getMeta(msg)->flags |= RF230PACKET_TIMESYNC;
-       }
-
-/*----------------- PacketSleepInterval -----------------*/
-
-       async command bool PacketSleepInterval.isSet(message_t* msg)
-       {
-               return getMeta(msg)->flags & RF230PACKET_LPL_SLEEPINT;
-       }
-
-       async command uint16_t PacketSleepInterval.get(message_t* msg)
-       {
-#ifdef LOW_POWER_LISTENING
-               return getMeta(msg)->lpl_sleepint;
-#else
-               return 0;
-#endif
-       }
-
-       async command void PacketSleepInterval.clear(message_t* msg)
-       {
-               getMeta(msg)->flags &= ~RF230PACKET_LPL_SLEEPINT;
-       }
-
-       async command void PacketSleepInterval.set(message_t* msg, uint16_t value)
-       {
-               getMeta(msg)->flags |= RF230PACKET_LPL_SLEEPINT;
-
-#ifdef LOW_POWER_LISTENING
-               getMeta(msg)->lpl_sleepint = value;
-#endif
-       }
-
-/*----------------- PacketLinkMetadata -----------------*/
-#ifdef PACKET_LINK
-
-       async command packet_link_metadata_t* PacketLinkMetadata.getData(message_t* msg)
-       {
-               return &(getMeta(msg)->packet_link);
-       }
-
-#endif
-}
diff --git a/tos/chips/rf2xx/util/IEEE154Packet2.h b/tos/chips/rf2xx/util/IEEE154Packet2.h
deleted file mode 100644 (file)
index 5c58007..0000000
+++ /dev/null
@@ -1,75 +0,0 @@
-/*
- * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
- * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
- * 
- * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
- * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
- *
- * Author: Miklos Maroti
- */
-
-#ifndef __IEEE154PACKET2_H__
-#define __IEEE154PACKET2_H__
-
-typedef nx_struct ieee154_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
-#ifndef TFRAMES_ENABLED        
-       nxle_uint8_t network;
-#endif
-
-       nxle_uint8_t type;
-} ieee154_header_t;
-
-// the actual radio driver might not use this
-typedef nx_struct ieee154_footer_t
-{ 
-       nxle_uint16_t crc;
-} ieee154_footer_t;
-
-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,
-       IEEE154_TYPE_MASK = 7,
-};
-
-enum iee154_fcf_addr_mode_enums {
-       IEEE154_ADDR_NONE = 0,
-       IEEE154_ADDR_SHORT = 2,
-       IEEE154_ADDR_EXT = 3,
-       IEEE154_ADDR_MASK = 3,
-};
-
-#endif//__IEEE154PACKET2_H__
diff --git a/tos/chips/rf2xx/util/IEEE154Packet2.nc b/tos/chips/rf2xx/util/IEEE154Packet2.nc
deleted file mode 100644 (file)
index 0957904..0000000
+++ /dev/null
@@ -1,197 +0,0 @@
-/*
- * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
- * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
- * 
- * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
- * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
- *
- * Author: Miklos Maroti
- */
-
-#include <IEEE154Packet2.h>
-#include <message.h>
-
-/**
- * This interface encapsulates IEEE 802.15.4 intrapan data frames with 
- * 16-bit destination pan, source and destination addresses. It also 
- * supports 6LowPan interoperability mode, and acknowledgement frames.
- * Note, that this interface does not support the CRC-16 value, which
- * should be verified before the data can be trusted.
- */
-interface IEEE154Packet2
-{
-       /**
-        * Returns the IEEE 802.15.4 header including the length field.
-        */
-       async command ieee154_header_t* getHeader(message_t* msg);
-
-       /**
-        * Returns the raw value (unadjusted) of the length field
-        */
-       async command uint8_t getLength(message_t* msg);
-
-       /**
-        * Sets the length field
-        */
-       async command void setLength(message_t* msg, uint8_t length);
-
-       /**
-        * Returns the frame control field. This method should not be used, 
-        * isDataFrame and isAckFrame should be used instead.
-        */
-       async command uint16_t getFCF(message_t* msg);
-
-       /**
-        * Sets the frame control field. This method should not be used, 
-        * createDataFrame and createAckFrame should be used instead.
-        */
-       async command void setFCF(message_t* msg, uint16_t fcf);
-
-       /**
-        * Returns TRUE if the message is a data frame supported by 
-        * this interface (based on the value of the FCF).
-        */
-       async command bool isDataFrame(message_t* msg);
-
-       /**
-        * Sets the FCF to create a data frame supported by this interface.
-        * You may call setAckRequired and setFramePending commands after this.
-        */
-       async command void createDataFrame(message_t* msg);
-
-       /**
-        * Returns TRUE if the message is an acknowledgement frame supported
-        * by this interface (based on the value of the FCF).
-        */
-       async command bool isAckFrame(message_t* msg);
-
-       /**
-        * Sets the FCF to create an acknowledgement frame supported by
-        * this interface. You may call setFramePending after this.
-        */
-       async command void createAckFrame(message_t* msg);
-
-       /**
-        * Creates an acknowledgement packet for the given data packet.
-        * This also sets the DSN value. The data message must be a 
-        * data frame, the ack message will be overwritten.
-        */
-       async command void createAckReply(message_t* data, message_t* ack);
-
-       /**
-        * Returns TRUE if the acknowledgement packet corresponds to the
-        * data packet. The data message must be a data packet.
-        */
-       async command bool verifyAckReply(message_t* data, message_t* ack);
-
-       /**
-        * Returns TRUE if the ACK required field is set in the FCF.
-        */
-       async command bool getAckRequired(message_t* msg);
-
-       /**
-        * Sets the ACK required field in the FCF, should never be set
-        * for acknowledgement frames.
-        */
-       async command void setAckRequired(message_t* msg, bool ack);
-
-       /**
-        * Returns TRUE if the frame pending field is set in the FCF.
-        */
-       async command bool getFramePending(message_t* msg);
-
-       /**
-        * Sets the frame pending field in the FCF.
-        */
-       async command void setFramePending(message_t* msg, bool pending);
-
-       /**
-        * Returns the data sequence number
-        */
-       async command uint8_t getDSN(message_t* msg);
-
-       /**
-        * Sets the data sequence number
-        */
-       async command void setDSN(message_t* msg, uint8_t dsn);
-
-       /**
-        * returns the destination PAN id, values <= 255 are tinyos groups,
-        * valid only for data frames
-        */
-       async command uint16_t getDestPan(message_t* msg);
-
-       /**
-        * Sets the destination PAN id, valid only for data frames
-        */
-       async command void setDestPan(message_t* msg, uint16_t pan);
-
-       /**
-        * Returns the destination address, valid only for data frames
-        */
-       async command uint16_t getDestAddr(message_t* msg);
-
-       /**
-        * Sets the destination address, valid only for data frames
-        */
-       async command void setDestAddr(message_t* msg, uint16_t addr);
-
-       /**
-        * Returns the source address, valid only for data frames
-        */
-       async command uint16_t getSrcAddr(message_t* msg);
-
-       /**
-        * Sets the source address, valid only for data frames
-        */
-       async command void setSrcAddr(message_t* msg, uint16_t addr);
-
-#ifndef TFRAMES_ENABLED
-
-       /**
-        * Returns the value of the 6LowPan network field.
-        */
-       async command uint8_t get6LowPan(message_t* msg);
-
-       /**
-        * Sets the value of the 6LowPan network field.
-        */
-       async command void set6LowPan(message_t* msg, uint8_t network);
-
-#endif
-
-       /**
-        * Returns the active message type of the message
-        */
-       async command am_id_t getType(message_t* msg);
-
-       /**
-        * Sets the active message type
-        */
-       async command void setType(message_t* msg, am_id_t type);
-
-       /**
-        * Returns TRUE if the packet is a data packet, the ACK_REQ field
-        * is set and the destination address is not the broadcast address.
-        */
-       async command bool requiresAckWait(message_t* msg);
-
-       /**
-        * Returns TRUE if the packet is a data packet, the ACK_REQ field
-        * is set and the destionation address is this node.
-        */
-       async command bool requiresAckReply(message_t* msg);
-}
diff --git a/tos/chips/rf2xx/util/IEEE154Packet2C.nc b/tos/chips/rf2xx/util/IEEE154Packet2C.nc
deleted file mode 100644 (file)
index c2fa14b..0000000
+++ /dev/null
@@ -1,40 +0,0 @@
-/*
- * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
- * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
- * 
- * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
- * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
- *
- * Author: Miklos Maroti
- */
-
-configuration IEEE154Packet2C
-{
-       provides
-       {
-               interface IEEE154Packet2;
-               interface AMPacket;
-       }
-}
-
-implementation
-{
-       components IEEE154Packet2P, ActiveMessageAddressC;
-       IEEE154Packet2P.ActiveMessageAddress -> ActiveMessageAddressC;
-
-       IEEE154Packet2 = IEEE154Packet2P;
-       AMPacket = IEEE154Packet2P;
-}
diff --git a/tos/chips/rf2xx/util/IEEE154Packet2P.nc b/tos/chips/rf2xx/util/IEEE154Packet2P.nc
deleted file mode 100644 (file)
index cb4ca8c..0000000
+++ /dev/null
@@ -1,294 +0,0 @@
-/*
- * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
- * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
- * 
- * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
- * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
- *
- * Author: Miklos Maroti
- */
-
-#include <IEEE154Packet2.h>
-
-module IEEE154Packet2P
-{
-       provides 
-       {
-               interface IEEE154Packet2;
-               interface AMPacket;
-       }
-
-       uses interface ActiveMessageAddress;
-}
-
-implementation
-{
-/*----------------- IEEE154Packet -----------------*/
-
-       enum
-       {
-               IEEE154_DATA_FRAME_MASK = (IEEE154_TYPE_MASK << IEEE154_FCF_FRAME_TYPE) 
-                       | (1 << IEEE154_FCF_INTRAPAN) 
-                       | (IEEE154_ADDR_MASK << IEEE154_FCF_DEST_ADDR_MODE) 
-                       | (IEEE154_ADDR_MASK << IEEE154_FCF_SRC_ADDR_MODE),
-
-               IEEE154_DATA_FRAME_VALUE = (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),
-
-               IEEE154_ACK_FRAME_LENGTH = 5,   // includes the FCF, DSN and FCS
-               IEEE154_ACK_FRAME_MASK = (IEEE154_TYPE_MASK << IEEE154_FCF_FRAME_TYPE), 
-               IEEE154_ACK_FRAME_VALUE = (IEEE154_TYPE_ACK << IEEE154_FCF_FRAME_TYPE),
-       };
-
-       inline ieee154_header_t* getHeader(message_t* msg)
-       {
-               return (ieee154_header_t*)(msg->data - sizeof(ieee154_header_t));
-       }
-
-       inline async command ieee154_header_t* IEEE154Packet2.getHeader(message_t* msg)
-       {
-               return getHeader(msg);
-       }
-
-       inline async command uint8_t IEEE154Packet2.getLength(message_t* msg)
-       {
-               return getHeader(msg)->length;
-       }
-
-       inline async command void IEEE154Packet2.setLength(message_t* msg, uint8_t length)
-       {
-               getHeader(msg)->length = length;
-       }
-
-       inline async command uint16_t IEEE154Packet2.getFCF(message_t* msg)
-       {
-               return getHeader(msg)->fcf;
-       }
-
-       inline async command void IEEE154Packet2.setFCF(message_t* msg, uint16_t fcf)
-       {
-               getHeader(msg)->fcf = fcf;
-       }
-
-       inline async command bool IEEE154Packet2.isDataFrame(message_t* msg)
-       {
-               return (getHeader(msg)->fcf & IEEE154_DATA_FRAME_MASK) == IEEE154_DATA_FRAME_VALUE;
-       }
-
-       inline async command void IEEE154Packet2.createDataFrame(message_t* msg)
-       {
-               getHeader(msg)->fcf = IEEE154_DATA_FRAME_VALUE;
-       }
-
-       inline async command bool IEEE154Packet2.isAckFrame(message_t* msg)
-       {
-               return (getHeader(msg)->fcf & IEEE154_ACK_FRAME_MASK) == IEEE154_ACK_FRAME_VALUE;
-       }
-
-       inline async command void IEEE154Packet2.createAckFrame(message_t* msg)
-       {
-               ieee154_header_t* header = getHeader(msg);
-
-               header->length = IEEE154_ACK_FRAME_LENGTH;
-               header->fcf = IEEE154_ACK_FRAME_VALUE;
-       }
-
-       inline async command void IEEE154Packet2.createAckReply(message_t* data, message_t* ack)
-       {
-               ieee154_header_t* header = getHeader(ack);
-
-               header->length = IEEE154_ACK_FRAME_LENGTH;
-               header->fcf = IEEE154_ACK_FRAME_VALUE;
-               header->dsn = getHeader(data)->dsn;
-       }
-
-       inline async command bool IEEE154Packet2.verifyAckReply(message_t* data, message_t* ack)
-       {
-               ieee154_header_t* header = getHeader(ack);
-
-               return header->dsn == getHeader(data)->dsn
-                       && (header->fcf & IEEE154_ACK_FRAME_MASK) == IEEE154_ACK_FRAME_VALUE;
-       }
-
-       inline async command bool IEEE154Packet2.getAckRequired(message_t* msg)
-       {
-               return getHeader(msg)->fcf & (1 << IEEE154_FCF_ACK_REQ);
-       }
-
-       inline async command void IEEE154Packet2.setAckRequired(message_t* msg, bool ack)
-       {
-               if( ack )
-                       getHeader(msg)->fcf |= (1 << IEEE154_FCF_ACK_REQ);
-               else
-                       getHeader(msg)->fcf &= ~(uint16_t)(1 << IEEE154_FCF_ACK_REQ);
-       }
-
-       inline async command bool IEEE154Packet2.getFramePending(message_t* msg)
-       {
-               return getHeader(msg)->fcf & (1 << IEEE154_FCF_FRAME_PENDING);
-       }
-
-       inline async command void IEEE154Packet2.setFramePending(message_t* msg, bool pending)
-       {
-               if( pending )
-                       getHeader(msg)->fcf |= (1 << IEEE154_FCF_FRAME_PENDING);
-               else
-                       getHeader(msg)->fcf &= ~(uint16_t)(1 << IEEE154_FCF_FRAME_PENDING);
-       }
-
-       inline async command uint8_t IEEE154Packet2.getDSN(message_t* msg)
-       {
-               return getHeader(msg)->dsn;
-       }
-
-       inline async command void IEEE154Packet2.setDSN(message_t* msg, uint8_t dsn)
-       {
-               getHeader(msg)->dsn = dsn;
-       }
-
-       inline async command uint16_t IEEE154Packet2.getDestPan(message_t* msg)
-       {
-               return getHeader(msg)->destpan;
-       }
-
-       inline async command void IEEE154Packet2.setDestPan(message_t* msg, uint16_t pan)
-       {
-               getHeader(msg)->destpan = pan;
-       }
-
-       inline async command uint16_t IEEE154Packet2.getDestAddr(message_t* msg)
-       {
-               return getHeader(msg)->dest;
-       }
-
-       inline async command void IEEE154Packet2.setDestAddr(message_t* msg, uint16_t addr)
-       {
-               getHeader(msg)->dest = addr;
-       }
-
-       inline async command uint16_t IEEE154Packet2.getSrcAddr(message_t* msg)
-       {
-               return getHeader(msg)->src;
-       }
-
-       inline async command void IEEE154Packet2.setSrcAddr(message_t* msg, uint16_t addr)
-       {
-               getHeader(msg)->src = addr;
-       }
-
-#ifndef TFRAMES_ENABLED
-
-       inline async command uint8_t IEEE154Packet2.get6LowPan(message_t* msg)
-       {
-               return getHeader(msg)->network;
-       }
-
-       inline async command void IEEE154Packet2.set6LowPan(message_t* msg, uint8_t network)
-       {
-               getHeader(msg)->network = network;
-       }
-
-#endif
-
-       inline async command am_id_t IEEE154Packet2.getType(message_t* msg)
-       {
-               return getHeader(msg)->type;
-       }
-
-       inline async command void IEEE154Packet2.setType(message_t* msg, am_id_t type)
-       {
-               getHeader(msg)->type = type;
-       }
-
-       async command bool IEEE154Packet2.requiresAckWait(message_t* msg)
-       {
-               return call IEEE154Packet2.getAckRequired(msg)
-                       && call IEEE154Packet2.isDataFrame(msg)
-                       && call IEEE154Packet2.getDestAddr(msg) != 0xFFFF;
-       }
-
-       async command bool IEEE154Packet2.requiresAckReply(message_t* msg)
-       {
-               return call IEEE154Packet2.getAckRequired(msg)
-                       && call IEEE154Packet2.isDataFrame(msg)
-                       && call IEEE154Packet2.getDestAddr(msg) == call ActiveMessageAddress.amAddress();
-       }
-
-       inline async event void ActiveMessageAddress.changed()
-       {
-       }
-
-/*----------------- AMPacket -----------------*/
-
-       inline command am_addr_t AMPacket.address()
-       {
-               return call ActiveMessageAddress.amAddress();
-       }
-       inline command am_group_t AMPacket.localGroup()
-       {
-               // TODO: check if this is correct
-               return call ActiveMessageAddress.amGroup();
-       }
-
-       inline command am_addr_t AMPacket.destination(message_t* msg)
-       {
-               return call IEEE154Packet2.getDestAddr(msg);
-       }
-       inline command am_addr_t AMPacket.source(message_t* msg)
-       {
-               return call IEEE154Packet2.getSrcAddr(msg);
-       }
-
-       inline command void AMPacket.setDestination(message_t* msg, am_addr_t addr)
-       {
-               call IEEE154Packet2.setDestAddr(msg, addr);
-       }
-
-       inline command void AMPacket.setSource(message_t* msg, am_addr_t addr)
-       {
-               call IEEE154Packet2.setSrcAddr(msg, addr);
-       }
-
-       inline command bool AMPacket.isForMe(message_t* msg)
-       {
-               am_addr_t addr = call AMPacket.destination(msg);
-               return addr == call AMPacket.address() || addr == AM_BROADCAST_ADDR;
-       }
-
-       inline command am_id_t AMPacket.type(message_t* msg)
-       {
-               return call IEEE154Packet2.getType(msg);
-       }
-
-       inline command void AMPacket.setType(message_t* msg, am_id_t type)
-       {
-               call IEEE154Packet2.setType(msg, type);
-       }
-  
-       inline command am_group_t AMPacket.group(message_t* msg) 
-       {
-               return call IEEE154Packet2.getDestPan(msg);
-       }
-
-       inline command void AMPacket.setGroup(message_t* msg, am_group_t grp)
-       {
-               call IEEE154Packet2.setDestPan(msg, grp);
-       }
-}
diff --git a/tos/chips/rf2xx/util/MetadataFlagC.nc b/tos/chips/rf2xx/util/MetadataFlagC.nc
new file mode 100644 (file)
index 0000000..1091eb5
--- /dev/null
@@ -0,0 +1,37 @@
+/*
+ * Copyright (c) 2009, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
+ * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ * 
+ * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
+ * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+ *
+ * Author: Miklos Maroti
+ */
+
+generic configuration MetadataFlagC()
+{
+       provides
+       {
+               interface PacketFlag;
+       }
+}
+
+implementation
+{
+       components MetadataFlagsLayerC;
+
+       PacketFlag = MetadataFlagsLayerC.PacketFlag[unique("PacketFlags")];
+}
index ea4259516ed9a14f05247f4d766f5ae6ee7e637e..b33382803aa1078fe84d83ce22a4a7e7dda6a9b8 100644 (file)
@@ -27,11 +27,11 @@ interface PacketData<data_t>
         * This command returns a pointer to a set of packet fields (in the header, footer 
         * or metadata) with the given data type.
         */
-       async command data_t* getData(message_t* msg);
+       async command data_t* get(message_t* msg);
 
        /**
         * This event is signalled, when the these fields should be reset to their default
         * value (usually called from Packet.clear)
         */
-       async event void clear(data_t* data);
+       async event void clear(message_t* msg);
 }
diff --git a/tos/chips/rf2xx/util/PacketFlag.nc b/tos/chips/rf2xx/util/PacketFlag.nc
new file mode 100644 (file)
index 0000000..3efabdb
--- /dev/null
@@ -0,0 +1,45 @@
+/*
+ * Copyright (c) 2007, Vanderbilt 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 THE VANDERBILT 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 THE VANDERBILT
+ * UNIVERSITY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ * 
+ * THE VANDERBILT 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 THE VANDERBILT UNIVERSITY HAS NO OBLIGATION TO
+ * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS, OR MODIFICATIONS.
+ *
+ * Author: Miklos Maroti
+ */
+
+interface PacketFlag
+{
+       /**
+        * Returns if the flag is set for this message. 
+        */
+       async command bool get(message_t* msg);
+
+       /**
+        * Sets the flag in this message to the specified value.
+        */
+       async command void setValue(message_t* msg, bool value);
+
+       /**
+        * Sets the flag in this message to TRUE
+        */
+       async command void set(message_t* msg);
+
+       /**
+        * Sets the flag in this message to FALSE
+        */
+       async command void clear(message_t* msg);
+}
index 2acab4c0d2612cb9806c7705d375260449ef5b20..04a764e873e09dc507baa1540c95b1738074b82e 100644 (file)
@@ -44,7 +44,7 @@ configuration TimeSyncMessageC
 
 implementation
 {
-       components GenericTimeSyncMessageC as MAC, LocalTimeMicroC, RF230PacketC;
+       components GenericTimeSyncMessageC as MAC, LocalTimeMicroC, RF230DriverLayerC;
   
        SplitControl    = MAC;
        Receive         = MAC.Receive;
@@ -57,6 +57,6 @@ implementation
        TimeSyncAMSendMilli     = MAC;
        TimeSyncPacketMilli     = MAC;
 
-       MAC.PacketTimeSyncOffset -> RF230PacketC.PacketTimeSyncOffset;
+       MAC.PacketTimeSyncOffset -> RF230DriverLayerC.PacketTimeSyncOffset;
        MAC.LocalTimeRadio -> LocalTimeMicroC;
 }
index 3753b4837ba600d3444e3717f4e8b0942d6aa521..dd4285a4dfcd6010b16dd48bf20bb7b989f1f624 100644 (file)
@@ -36,6 +36,7 @@ configuration HplRF230C
 
                interface GpioCapture as IRQ;
                interface Alarm<TRadio, uint16_t> as Alarm;
+               interface LocalTime<TRadio> as LocalTimeRadio;
        }
 }
 
@@ -64,4 +65,7 @@ implementation
 
        components RealMainP;
        RealMainP.PlatformInit -> HplRF230P.PlatformInit;
+
+       components LocalTimeMicroC;
+       LocalTimeRadio = LocalTimeMicroC;
 }
index 6f598905da0414c0ea205dee6a49e349af96e44a..f3896a0f882143c920d7f3e60431a06dc271647a 100644 (file)
@@ -25,7 +25,7 @@
 #define __RADIOCONFIG_H__
 
 #include <MicaTimer.h>
-#include <RF230.h>
+#include <RF230DriverLayer.h>
 #include <util/crc16.h>
 
 enum
index e3245c968a17ac9c375b83492e3e4f0d4d4c00c1..387d74fe34b04072aeec3f7ffeeb8d6030a072f6 100644 (file)
@@ -23,7 +23,7 @@
 #ifndef PLATFORM_MESSAGE_H
 #define PLATFORM_MESSAGE_H
 
-#include <RF230Packet.h>
+#include <RF230ActiveMessage.h>
 #include <Serial.h>
 
 typedef union message_header {