Skip to content

Commit

Permalink
Fix: Standby-I in sleep mode, other changes
Browse files Browse the repository at this point in the history
Finalization of enhanced sleep mode:
* 1. The radio is configured to use Dynamic Payloads and ACK payloads
with Auto-Ack enabled
* 2. The radio enters PTX mode and attaches an interrupt handler to the
radio interrupt input pin (pin 2)
* 3. The radio uses the Watchdog Timer to awake at set 1 second
intervals in the example file
* 4. Every interval, it sends out a 'sleep' payload and goes back to
sleep. Incoming payloads will then be treated as ACK payloads, while the
radio remains in STANDBY-I mode.
* 5. If an interrupt is triggered, the radio wakes up
* 6. When a message is sent to the sleeping node, the interrupt triggers
a wake up, the MCU
* grabs the payload, and switches back to receive mode in case more data
is on its way.

Compared to receive mode:
* The radio will draw about 13.5 mA in normal receiver mode.
* In STANDBY-I mode, the radio draws .000022mA, and is able to awake
when payloads are received.

Changed Radio initialization:
- Uses new radio.maskIRQ function to disable TX and MAX_RT interrupts
for sleep mode

- Added code to discard sleep payloads
- Added function for custom initialization of watchdog timer intervals
  • Loading branch information
TMRh20 committed Apr 5, 2014
1 parent 0e24467 commit f88f3cb
Show file tree
Hide file tree
Showing 5 changed files with 159 additions and 135 deletions.
97 changes: 64 additions & 33 deletions RF24Network.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,15 +9,18 @@
#include "RF24Network_config.h"
#include "RF24.h"
#include "RF24Network.h"
#include <avr/sleep.h>
#include <avr/power.h>

#ifndef __arm__
#include <avr/sleep.h>
#include <avr/power.h>
#endif

uint16_t RF24NetworkHeader::next_id = 1;

uint64_t pipe_address( uint16_t node, uint8_t pipe );
bool is_valid_address( uint16_t node );

volatile short sleepCounter = 0;
volatile byte sleep_cycles_remaining;

/******************************************************************/

Expand All @@ -42,6 +45,13 @@ void RF24Network::begin(uint8_t _channel, uint16_t _node_address )
radio.setDataRate(RF24_1MBPS);
radio.setCRCLength(RF24_CRC_16);

radio.maskIRQ(1,1,0); //TX,FAIL,RX
radio.enableAckPayload();
radio.enableDynamicPayloads();
radio.setPayloadSize(frame_size);
radio.setAutoAck(1);


// Setup our address helper cache
setup_address();

Expand All @@ -50,9 +60,7 @@ void RF24Network::begin(uint8_t _channel, uint16_t _node_address )
while (i--)
radio.openReadingPipe(i,pipe_address(_node_address,i));
radio.startListening();

// Spew debugging state about the radio
radio.printDetails();
radio.powerUp();
}

/******************************************************************/
Expand Down Expand Up @@ -80,6 +88,14 @@ void RF24Network::update(void)
if ( !is_valid_address(header.to_node) )
continue;


//TMRh20
// Throw it away if its a sleep packet
if (header.type == 'S'){
continue; //Discard the payload

}

// Is this for us?
if ( header.to_node == node_address )
// Add it to the buffer of frames for us
Expand Down Expand Up @@ -447,44 +463,59 @@ uint64_t pipe_address( uint16_t node, uint8_t pipe )
/************************ Sleep Mode ******************************************/


void wakeUp(){ // Interrupt for waking up


#if !defined( __AVR_ATtiny85__ ) || defined( __AVR_ATtiny84__) || defined(__arm__)

RF24NetworkHeader sleepHeader(/*to node*/ 00, /*type*/ 'S' /*Sleep*/);

bool awoke = 0;

void wakeUp(){
//detachInterrupt(0);
sleep_disable();
sleep_cycles_remaining = 0;
awoke = 1;
}

ISR(WDT_vect){
--sleepCounter; // Decrement the sleep cycle counter
}
--sleep_cycles_remaining;

void goToSleep(int pin){
set_sleep_mode(SLEEP_MODE_PWR_DOWN); // sleep mode is set here
sleep_enable();
WDTCSR |= _BV(WDIE);
if(pin != 255){
attachInterrupt(pin,wakeUp,FALLING);
}
sleep_mode();
}


void RF24Network::sleepNode( unsigned int cycles, int interruptPin ){

pinMode(interruptPin,INPUT_PULLUP);
digitalWrite(interruptPin,HIGH);
if(cycles > 0){
sleepCounter = cycles;
MCUSR &= ~_BV(WDRF); // Clear the WDT System Reset Flag
WDTCSR = _BV(WDCE) | _BV(WDE); // Write the WDT Change enable bit to enable changing the prescaler and enable system reset
WDTCSR = _BV(WDCE) | B00000110; // Write the prescalar bits (1second sleep cycles

while(sleepCounter > 0){ // If using WDT, sleep for
goToSleep(interruptPin);
}
}else{
goToSleep(interruptPin);
} // The WDT_vect interrupt wakes the MCU from here
sleep_disable(); // System continues execution here when watchdog timed out
detachInterrupt(interruptPin); // Detach the pin interrupt

sleep_cycles_remaining = cycles;
set_sleep_mode(SLEEP_MODE_PWR_DOWN); // sleep mode is set here
sleep_enable();
if(interruptPin != 255){
attachInterrupt(interruptPin,wakeUp,LOW);
}
WDTCSR |= _BV(WDIE);
while(sleep_cycles_remaining){
uint8_t junk = 23;
write(sleepHeader,&junk,1);
sleep_mode(); // System sleeps here
} // The WDT_vect interrupt wakes the MCU from here
sleep_disable(); // System continues execution here when watchdog timed out
if(awoke){ update(); awoke = 0; }
detachInterrupt(interruptPin);
WDTCSR &= ~_BV(WDIE);
radio.startListening();

}

void RF24Network::setup_watchdog(uint8_t prescalar){

uint8_t wdtcsr = prescalar & 7;
if ( prescalar & 8 )
wdtcsr |= _BV(WDP3);
MCUSR &= ~_BV(WDRF); // Clear the WD System Reset Flag
WDTCSR = _BV(WDCE) | _BV(WDE); // Write the WD Change enable bit to enable changing the prescaler and enable system reset
WDTCSR = _BV(WDCE) | wdtcsr | _BV(WDIE); // Write the prescalar bits (how long to sleep, enable the interrupt to wake the MCU
}


#endif
63 changes: 34 additions & 29 deletions RF24Network.h
Original file line number Diff line number Diff line change
Expand Up @@ -163,11 +163,10 @@ class RF24Network
/**
* Sleep this node
* @note NEW - Nodes can now be slept while the radio is not actively transmitting.
* @note Setting cycles to 0 will disable the timed wakeup.
* @note Setting the interruptPin to 255 will disable interrupt wake-ups
*
* This function will sleep the node only, while leaving the radio active in StandBy-I mode, which consumes
* 22uA compared to 0.9uA in full powerDown() mode.
* This function will sleep the node, with the radio mostly powered down in StandBy-I mode, which consumes
* .000022mA compared to 13.5mA in receive mode.
*
* The node can be awoken in two ways, both of which can be enabled simultaneously:
* 1. An interrupt - usually triggered by the radio receiving a payload. Must use pin 2 (interrupt 0) or 3 (interrupt 1) on Uno, Nano, etc.
Expand All @@ -176,15 +175,27 @@ class RF24Network
* if(!network.available()){ network.sleepNode(1,0); } //Sleeps the node for 1 second or a payload is received
*
* Other options:
* network.sleepNode(0,0); // Sleep this node forever or until a payload is received.
* network.sleepNode(1,255); // Sleep this node for 1 second. Do not wake up until then, even if a payload is received ( no interrupt )
* network.sleepNode(0,0); // Sleep this node for the designated time period, or a payload is received.
* network.sleepNode(1,255); // Sleep this node for 1 cycle. Do not wake up until then, even if a payload is received ( no interrupt )
* @endcode
* @param Cycles: The node will sleep in cycles of 1s. Using 2 will sleep 2 seconds, 3 sleeps 3s...
* @see setup_watchdog()
* @param cycles: The node will sleep in cycles of 1s. Using 2 will sleep 2 WDT cycles, 3 sleeps 3WDT cycles...
* @param interruptPin: The interrupt number to use (0,1) for pins two and three on Uno,Nano. More available on Mega etc.
*
*/
void sleepNode( unsigned int cycles, int interruptPin );

/**
* Set up the watchdog timer for sleep mode using the number 0 through 10 to represent the following time periods:<br>
* wdt_16ms = 0, wdt_32ms, wdt_64ms, wdt_128ms, wdt_250ms, wdt_500ms, wdt_1s, wdt_2s, wdt_4s, wdt_8s
* @code
* setup_watchdog(7); // Sets the WDT to trigger every second
* @endcode
* @param prescalar The WDT prescaler to define how often the node will wake up. When defining sleep mode cycles, this time period is 1 cycle.
*/
void setup_watchdog(uint8_t prescalar);


/**
* This node's parent address
*
Expand Down Expand Up @@ -246,26 +257,20 @@ class RF24Network
*/

/**
* @example Network_Sleep_Timeouts.ino
* @example Network_Ping_Sleep.ino
*
* Example: This is almost exactly the same as the Network_Ping example, but with use
* of the integrated sleep mode and extended timeout periods.
*
* <br><br>
* <b> &nbsp;&nbsp;&nbsp; SLEEP_MODE: </b>
* - Sleep mode is set with the command radio.sleepNode(<seconds>, <interrupt pin>); <br>
* - The node itself will sleep, with the radio in Standby-I mode, drawing 22uA compared to .9uA in powerdown mode. <br>
* - Sleep mode uses the WatchDog Timer (WDT) to sleep in 1-second intervals, or is awoken by the radio interrupt pin going <br>
* high, which indicates that a payload has been received. This allows much more efficient power use among the entire network. <br>
* - Max value is 65535 which sleeps for about 18 hours. <br>
* - The node power use can be reduced further by disabling unnessessary systems via the Power Reduction Register(s) (PRR) and by putting<br>
* the radio into full sleep mode ( radio.powerDown() ), but it will not receive or send until powered up again.<br>
* <br>
* <b> EXTENDED TIMEOUTS: </b><br>
* - This sketch utilizes newly introduced extended timeout periods to ensure reliability in transmission of payloads.<br>
* - Users should be careful not to set too high a value on nodes that will receive data regularly, since payloads may be missed while<br>
* retrying failed payloads. The maximum retry period at (15,15) = 16 time periods * 250us retry delay * 15 retries = 60ms per payload.<br>
* - Setting this value lower than the calculated retry period will have no effect.<br>
* of the integrated sleep mode.
*
* This example demonstrates how nodes on the network utilize sleep mode to conserve power. For example,
* the radio itself will draw about 13.5mA in receive mode. In sleep mode, it will use as little as 22ua (.000022mA)
* of power when not actively transmitting or receiving data. In addition, the Arduino is powered down as well,
* dropping network power consumption dramatically compared to previous capabilities. <br>
* Note: Sleeping nodes generate traffic that will wake other nodes up. This may be mitigated with further modifications. Sleep
* payloads are currently always routed to the master node, which will wake up intermediary nodes. Routing nodes can be configured
* to go back to sleep immediately.
* The displayed millis() count will give an indication of how much a node has been sleeping compared to the others, as millis() will
* not increment while a node sleeps.
*<br>
* - Using this sketch, each node will send a ping to every other node in the network every few seconds.<br>
* - The RF24Network library will route the message across the mesh to the correct node.<br>
Expand Down Expand Up @@ -304,7 +309,7 @@ class RF24Network
* @section Features Features
*
* The layer provides:
* @li <b>New</b> (2014): Power efficient listening. Nodes can now sleep for extended periods of time with minimal power usage:
* @li <b>New</b> (2014): Power efficient sleep mode. Nodes can now sleep for extended periods of time with minimal power usage:
* StandBy-I mode uses 22uA compared to 0.9uA in full power down mode. The Arduino is allowed to sleep,
* and is awoken via interrupt when payloads are received, or via a user defined time period. See the docs.
* @li <b>New</b> (2014): Extended timeouts. The maximum timeout period is approximately 60ms per payload with max delay between retries, and
Expand All @@ -323,8 +328,8 @@ class RF24Network
*
* @section More How to learn more
*
* @li <a href="http://tmrh20.github.com/RF24/">RF24: Underlying radio driver</a>
* @li <a href="classRF24Network.html">RF24Network Class Documentation</a>
* @li <a href="http://tmrh20.github.com/RF24/">RF24: Underlying radio driver</a>
* @li <a href="http://tmrh20.blogspot.com/2014/03/high-speed-data-transfers-and-wireless.html">My Blog: RF24 Optimization Overview</a>
* @li <a href="http://tmrh20.blogspot.com/2014/03/arduino-radiointercomwireless-audio.html">My Blog: RF24 Wireless Audio</a>
* @li <a href="https://github.com/TMRh20/RF24Network/archive/master.zip">Download Current Package</a>
Expand Down Expand Up @@ -356,9 +361,9 @@ class RF24Network
*| | | 00 | | | 00 | | | | Master Node (00) |
*|---|----|----|----|----|----|----|----|----|-----------------------------------------------------|
*| | | 01 | | | 04 | | | | 1st level children of master (00) |
*| | 011| |021 | | |014 | | | 2nd level children of master. Children of 1st level.|
*|111| | | |121 | | | 114| | 3rd level children of master. Children of 2nd level.|
*| | | | |1114| |1114|2114|3114| 4th level children of master. Children of 3rd level.|
*| | 011| | 021| | |014 | | | 2nd level children of master. Children of 1st level.|
*|111| | | 121| 221| | | 114| | 3rd level children of master. Children of 2nd level.|
*| | | | |1221| |1114|2114|3114| 4th level children of master. Children of 3rd level.|
*
* @section Routing How routing is handled
*
Expand Down
3 changes: 2 additions & 1 deletion RF24Network_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ extern HardwareSPI SPI;

// Progmem is Arduino-specific
#ifdef ARDUINO

#include <avr/pgmspace.h>
#define PRIPSTR "%S"
#else
Expand All @@ -53,7 +54,7 @@ typedef uint16_t prog_uint16_t;
#define printf_P printf
#define strlen_P strlen
#define PROGMEM
#define pgm_read_word(p) (*(p))
#define pgm_read_word(p) (*(p))
#define PRIPSTR "%s"
#endif

Expand Down
Loading

0 comments on commit f88f3cb

Please sign in to comment.