Skip to content

Commit

Permalink
Major changes - Network ACKs, Fixes
Browse files Browse the repository at this point in the history
Major Change: Changes to message types will require re-installation on
ALL NODES
Enable no-network-ack for certain message types. Users can control
whether then network will send an ACK response for routed payloads.
Message types 1 through 64 will NOT receive a network ACK. This is
useful when expecting a response from the recipient, as an ACK is not
always needed.

- Fix: bad dynamic payload handling on Arduino (resulted in
corrupt/messed up responses)
- Fix: debug on RPi
- Change network response types (requires re-install on all nodes)
- Add network_ping system message type
  • Loading branch information
TMRh20 committed Oct 8, 2014
1 parent c73eabc commit 1560be5
Show file tree
Hide file tree
Showing 4 changed files with 155 additions and 97 deletions.
15 changes: 10 additions & 5 deletions RF24Network.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,6 +133,10 @@ uint8_t RF24Network::update(void)
IF_SERIAL_DEBUG_ROUTING( printf_P(PSTR("MAC: System payload rcvd %d\n"),res); );
return res;
}
if(res == NETWORK_PING){
returnVal = NETWORK_PING;
continue;
}
if(header.type == NETWORK_ADDR_RESPONSE ){
uint16_t requester = frame_buffer[8];// | frame_buffer[9] << 8;
requester |= frame_buffer[9] << 8;
Expand Down Expand Up @@ -323,7 +327,8 @@ bool RF24Network::write(RF24NetworkHeader& header,const void* message, size_t le
}
/******************************************************************/
bool RF24Network::write(RF24NetworkHeader& header,const void* message, size_t len, uint16_t writeDirect){

dynLen=sizeof(RF24NetworkHeader)+len;
dynLen=min(dynLen,MAX_FRAME_SIZE);
#if defined (DISABLE_FRAGMENTATION)
return _write(header,message,len,writeDirect);
#else
Expand Down Expand Up @@ -476,7 +481,7 @@ bool RF24Network::write(uint16_t to_node, uint8_t directTo) // Direct To: 0 = F

if(!ok){ IF_SERIAL_DEBUG_ROUTING( printf_P(PSTR("%lu: MAC Send fail to 0%o via 0%o on pipe %x\n\r"),millis(),to_node,conversion.send_node,conversion.send_pipe);); }

if( directTo == TX_ROUTED && ok && conversion.send_node == to_node && frame_buffer[6] != NETWORK_ACK && frame_buffer[6] != NETWORK_REQ_ADDRESS){
if( directTo == TX_ROUTED && ok && conversion.send_node == to_node && frame_buffer[6] > 64 && frame_buffer[6] < 192){

RF24NetworkHeader& header = * reinterpret_cast<RF24NetworkHeader*>(frame_buffer);
header.type = NETWORK_ACK; // Set the payload type to NETWORK_ACK
Expand All @@ -491,15 +496,15 @@ bool RF24Network::write(uint16_t to_node, uint8_t directTo) // Direct To: 0 = F
//dynLen=0;
IF_SERIAL_DEBUG_ROUTING( printf_P(PSTR("%lu MAC: Route OK to 0%o ACK sent to 0%o\n"),millis(),to_node,header.to_node); );
}

dynLen=0;
// if(!ok){ printf_P(PSTR("%lu: MAC No Ack from 0%o via 0%o on pipe %x\n\r"),millis(),to_node,send_node,send_pipe); }

#if !defined (DUAL_HEAD_RADIO)
// Now, continue listening
radio.startListening();
#endif

if( ok && conversion.send_node != to_node && (directTo==0 || directTo==3) && frame_buffer[6] != NETWORK_REQ_ADDRESS){
if( ok && conversion.send_node != to_node && (directTo==0 || directTo==3) && frame_buffer[6] > 64 && frame_buffer[6] < 192){
uint32_t reply_time = millis();
while( update() != NETWORK_ACK){
if(millis() - reply_time > routeTimeout){
Expand Down Expand Up @@ -584,7 +589,7 @@ bool RF24Network::write_to_pipe( uint16_t node, uint8_t pipe, bool multicast )
radio.openWritingPipe(out_pipe);
size_t wLen = dynLen ? dynLen: frame_size;
radio.writeFast(&frame_buffer, wLen,multicast);
dynLen=0;

ok = radio.txStandBy(txTimeout);


Expand Down
190 changes: 115 additions & 75 deletions RF24Network.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,21 +32,29 @@
#define MIN_USER_DEFINED_HEADER_TYPE 0
#define MAX_USER_DEFINED_HEADER_TYPE 127


#define NETWORK_ACK_REQUEST 128
#define NETWORK_ACK 129
#define NETWORK_REQ_ADDRESS 151
#define NETWORK_ADDR_RESPONSE 152
#define NETWORK_ADDR_CONFIRM 153

/**System-Sub Types (0-255)*/
//#define NETWORK_REQ_STREAM 11;
#define NETWORK_POLL 130
/**
* Network Response Types
* The network will determine whether to automatically acknowledge payloads based on their type
* For User types (1-127) 1-64 will NOT be acknowledged
* For System types (128-255) 192 through 255 will NOT be acknowledged
*/
// ACK Response Types
#define NETWORK_ADDR_RESPONSE 128
#define NETWORK_ADDR_CONFIRM 129
#define NETWORK_PING 130

#define NETWORK_FIRST_FRAGMENT 148
#define NETWORK_MORE_FRAGMENTS 149
#define NETWORK_LAST_FRAGMENT 150

// NO ACK Response Types
#define NETWORK_ACK_REQUEST 192
#define NETWORK_ACK 193
#define NETWORK_POLL 194
#define NETWORK_REQ_ADDRESS 195





/** Defines for handling written payloads */
Expand All @@ -56,12 +64,12 @@
#define USER_TX_TO_LOGICAL_ADDRESS 3 // network ACK
#define USER_TX_MULTICAST 4


/** System defines */
#define MAX_FRAME_SIZE 32
#define MAX_PAYLOAD_SIZE 1500



class RF24;

/**
Expand All @@ -74,6 +82,12 @@ struct RF24NetworkHeader
uint16_t from_node; /**< Logical address where the message was generated */
uint16_t to_node; /**< Logical address where the message is going */
uint16_t id; /**< Sequential message ID, incremented every message */
/**
* Message Types:
* User message types 1 through 64 will NOT be acknowledged by the network. Message types 65 through 127 will receive a network ACK. <br>
* System message types 192 through 255 will NOT be acknowledged by the network. Message types 128 through 192 will receive a network ACK.
* When requesting a response from another node, for example, a network ACK is not required, and will add extra traffic to the network.
*/
unsigned char type; /**< Type of the packet. 0-127 are user-defined types, 128-255 are reserved for system */
unsigned char reserved; /**< Reserved for future use */

Expand Down Expand Up @@ -125,6 +139,7 @@ struct RF24NetworkHeader
* Frame structure for each message
*
* The frame put over the air consists of a header and a message payload
* @note Frames are handled internally for fragmented payloads. Use RF24NetworkHeader
*/


Expand Down Expand Up @@ -209,7 +224,7 @@ class RF24Network
*/
void begin(uint8_t _channel, uint16_t _node_address );

void failures(uint32_t *_fails, uint32_t *_ok);

/**
* Main layer loop
*
Expand Down Expand Up @@ -262,66 +277,7 @@ class RF24Network
* @return Whether the message was successfully received
*/
bool write(RF24NetworkHeader& header,const void* message, size_t len);
bool write(RF24NetworkHeader& header,const void* message, size_t len, uint16_t writeDirect);

/**
* Send a multicast message to multiple nodes at once
* Allows messages to be rapidly broadcast through the network
*
* Multicasting is arranged in levels, with all nodes on the same level listening to the same address
* Levels are assigned by network level ie: nodes 01-05: Level 1, nodes 011-055: Level 2
* @see multicastLevel
* @param message Pointer to memory where the message is located
* @param len The size of the message
* @param level Multicast level to broadcast to
* @return Whether the message was successfully received
*/

bool multicast(RF24NetworkHeader& header,const void* message, size_t len, uint8_t level);

/**
* Sleep this node - Still Under Development
* @note NEW - Nodes can now be slept while the radio is not actively transmitting. This must be manually enabled by uncommenting
* the #define ENABLE_SLEEP_MODE in RF24Network_config.h
* @note Setting the interruptPin to 255 will disable interrupt wake-ups
* @note The watchdog timer should be configured in setup() if using sleep mode.
* This function will sleep the node, with the radio still active 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.
* 2. The watchdog timer waking the MCU after a designated period of time, can also be used instead of delays to control transmission intervals.
* @code
* 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 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
* @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
*
* @return This node's parent address, or -1 if this is the base
*/
uint16_t parent() const;

/**@}*/
/**
* @name Advanced Operation
Expand All @@ -332,7 +288,7 @@ class RF24Network

/**
* Construct the network in dual head mode using two radio modules.
* @note Radios will share MISO, MOSI and SCK pins, but require separate CE,CS pins.
* @note Not working on RPi. Radios will share MISO, MOSI and SCK pins, but require separate CE,CS pins.
* @code
* RF24 radio(7,8);
* RF24 radio1(4,5);
Expand All @@ -354,19 +310,44 @@ class RF24Network
*
*/

uint32_t txTimeout;
uint32_t txTimeout; /**< Network timeout value */

/**
* @note: Optimization: This new value defaults to 200 milliseconds.
* This only affects payloads that are routed by one or more nodes.
* This specifies how long to wait for an ack from across the network.
* Radios routing directly to their parent or children nodes do not
* utilize this value.
*/

uint16_t routeTimeout;
uint16_t routeTimeout; /**< Timeout for routed payloads */

/**
* Return the number of failures and successes for all transmitted payloads, routed or sent directly
* @code
* bool fails, success;
* network.failures(&fails,&success);
* @endcode
*
*/
void failures(uint32_t *_fails, uint32_t *_ok);

#if defined (RF24NetworkMulticast)

/**
* Send a multicast message to multiple nodes at once
* Allows messages to be rapidly broadcast through the network
*
* Multicasting is arranged in levels, with all nodes on the same level listening to the same address
* Levels are assigned by network level ie: nodes 01-05: Level 1, nodes 011-055: Level 2
* @see multicastLevel
* @param message Pointer to memory where the message is located
* @param len The size of the message
* @param level Multicast level to broadcast to
* @return Whether the message was successfully received
*/

bool multicast(RF24NetworkHeader& header,const void* message, size_t len, uint8_t level);

/**
* By default, multicast addresses are divided into levels. Nodes 1-5 share a multicast address,
* nodes n1-n5 share a multicast address, and nodes n11-n55 share a multicast address. This option
Expand All @@ -389,7 +370,66 @@ class RF24Network


#endif

/**
* Writes a direct payload. This allows routing or sending messages outside of the usual routing paths.
* The same as write, but a physical address is specified as the last option.
* The payload will be written to the physical address, and routed as necessary by the recipient
*/
bool write(RF24NetworkHeader& header,const void* message, size_t len, uint16_t writeDirect);

/**
* Sleep this node - Still Under Development
* @note NEW - Nodes can now be slept while the radio is not actively transmitting. This must be manually enabled by uncommenting
* the #define ENABLE_SLEEP_MODE in RF24Network_config.h
* @note Setting the interruptPin to 255 will disable interrupt wake-ups
* @note The watchdog timer should be configured in setup() if using sleep mode.
* This function will sleep the node, with the radio still active 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.
* 2. The watchdog timer waking the MCU after a designated period of time, can also be used instead of delays to control transmission intervals.
* @code
* 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 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
* @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
*
* @return This node's parent address, or -1 if this is the base
*/
uint16_t parent() const;

/**
* Provided a node address and a pipe number, will return the RF24Network address of that child pipe for that node
*/
uint16_t addressOfPipe( uint16_t node,uint8_t pipeNo );

/**
* @note Addresses are specified in octal: 011, 034
* @return True if a supplied address is valid
*/
bool is_valid_address( uint16_t node );

private:
Expand Down
17 changes: 11 additions & 6 deletions RPi/RF24Network/RF24Network.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ void RF24Network::begin(uint8_t _channel, uint16_t _node_address ) {
node_address = _node_address;

if ( ! radio.isValid() ) {
printf("invalid radio\n");
return;
}
radio.stopListening();
Expand Down Expand Up @@ -121,7 +122,7 @@ uint8_t RF24Network::update(void) {
}

// Throw it away if it's not a valid address
if ( !is_valid_address(header.to_node) ) {
if ( !is_valid_address(header.to_node) ){
continue;
}

Expand All @@ -134,9 +135,13 @@ uint8_t RF24Network::update(void) {
if ( header.to_node == node_address ) {

if (header.type == NETWORK_ACK || (header.type == NETWORK_REQ_ADDRESS && !node_address) || header.type == NETWORK_ADDR_CONFIRM ) {
IF_SERIAL_DEBUG_ROUTING(printf_P(PSTR("RT: System payload rcvd %d\n"),res););
IF_SERIAL_DEBUG_ROUTING(printf_P(PSTR("RT: System payload rcvd %d\n"),header.type););
return header.type;
}
if(header.type == NETWORK_PING){
returnVal = NETWORK_PING;
continue;
}
if(header.type == NETWORK_ADDR_RESPONSE ){
uint16_t requester = frame_buffer[8];// | frame_buffer[9] << 8;
requester |= frame_buffer[9] << 8;
Expand Down Expand Up @@ -614,7 +619,7 @@ bool RF24Network::write(uint16_t to_node, uint8_t directTo) {
#endif


if ( directTo == 1 && ok && conversion.send_node == to_node && frame_buffer[6] != NETWORK_ACK ) {
if ( directTo == 1 && ok && conversion.send_node == to_node && frame_buffer[6] > 64 && frame_buffer[6] < 192 ) {

//RF24NetworkHeader& header = * reinterpret_cast<RF24NetworkHeader*>(frame_buffer);
frame_buffer[6] = NETWORK_ACK; // Set the payload type to NETWORK_ACK
Expand All @@ -629,21 +634,21 @@ bool RF24Network::write(uint16_t to_node, uint8_t directTo) {
//Write the data using the resulting physical address
write_to_pipe(conversion.send_node, conversion.send_pipe, multicast);

IF_SERIAL_DEBUG_ROUTING(printf("RT Route OK to 0%o ACK sent to 0%o\n",to_node,header.to_node););
IF_SERIAL_DEBUG_ROUTING(printf("RT Route OK to 0%o ACK sent to 0%o\n",to_node,conversion.send_node););
}

//if (!noListen ) {
radio.startListening();
//}

if ( ok && (conversion.send_node != to_node) && (directTo==0 || directTo == 3 )) {
if ( ok && (conversion.send_node != to_node) && (directTo==0 || directTo == 3 ) && frame_buffer[6] > 64 && frame_buffer[6] < 192) {

uint32_t reply_time = millis();
//Wait for NETWORK_ACK
while( update() != NETWORK_ACK) {
if (millis() - reply_time > routeTimeout) {
ok = 0;
IF_SERIAL_DEBUG_ROUTING(printf_P(PSTR("%u: RT Network ACK fail from 0%o via 0%o on pipe %x\n\r"),millis(),logicalAddress,send_node,send_pipe););
IF_SERIAL_DEBUG_ROUTING(printf_P(PSTR("%u: RT Network ACK fail from 0%o via 0%o on pipe %x\n\r"),millis(),to_node,conversion.send_node,conversion.send_pipe););
break;
}
}
Expand Down
Loading

0 comments on commit 1560be5

Please sign in to comment.