Commit b7c24a81 authored by TMRh20's avatar TMRh20

Updated address assignment

- Added setAddressWidth()  - allows address widths of 3 to 5 bytes
(24,32 or 40 bits)
- Addresses can now be specified via a byte array
- Thanks to Zephyrr for suggestion
parent b7e4a09a
......@@ -330,8 +330,7 @@ void RF24::print_address_register(const char* name, uint8_t reg, uint8_t qty)
RF24::RF24(uint8_t _cepin, uint8_t _cspin):
ce_pin(_cepin), csn_pin(_cspin), wide_band(false), p_variant(false),
payload_size(32), dynamic_payloads_enabled(false),
pipe0_reading_address(0)
payload_size(32), dynamic_payloads_enabled(false),addr_width(5)//,pipe0_reading_address(0)
{
}
......@@ -515,7 +514,7 @@ void RF24::startListening(void)
// Restore the pipe0 adddress, if exists
if (pipe0_reading_address){
write_register(RX_ADDR_P0, reinterpret_cast<const uint8_t*>(&pipe0_reading_address), 5);
write_register(RX_ADDR_P0, pipe0_reading_address, addr_width);
}
// Flush buffers
......@@ -821,7 +820,20 @@ void RF24::openWritingPipe(uint64_t value)
}
/****************************************************************************/
void RF24::openWritingPipe(const uint8_t *address)
{
// Note that AVR 8-bit uC's store this LSB first, and the NRF24L01(+)
// expects it LSB first too, so we're good.
write_register(RX_ADDR_P0,address, addr_width);
write_register(TX_ADDR, address, addr_width);
//const uint8_t max_payload_size = 32;
//write_register(RX_PW_P0,min(payload_size,max_payload_size));
write_register(RX_PW_P0,payload_size);
}
/****************************************************************************/
static const uint8_t child_pipe[] PROGMEM =
{
RX_ADDR_P0, RX_ADDR_P1, RX_ADDR_P2, RX_ADDR_P3, RX_ADDR_P4, RX_ADDR_P5
......@@ -841,7 +853,7 @@ void RF24::openReadingPipe(uint8_t child, uint64_t address)
// openWritingPipe() will overwrite the pipe 0 address, so
// startListening() will have to restore it.
if (child == 0)
pipe0_reading_address = address;
pipe0_reading_address = reinterpret_cast<uint8_t*>(&address);
if (child <= 6)
{
......@@ -860,6 +872,44 @@ void RF24::openReadingPipe(uint8_t child, uint64_t address)
}
}
/****************************************************************************/
void RF24::setAddressWidth(uint8_t a_width){
if(a_width -= 2){
write_register(SETUP_AW,a_width%4);
addr_width = (a_width%4) + 2;
}
}
/****************************************************************************/
void RF24::openReadingPipe(uint8_t child, const uint8_t *address)
{
// If this is pipe 0, cache the address. This is needed because
// openWritingPipe() will overwrite the pipe 0 address, so
// startListening() will have to restore it.
if (child == 0)
pipe0_reading_address = address;
if (child <= 6)
{
// For pipes 2-5, only write the LSB
if ( child < 2 ){
write_register(pgm_read_byte(&child_pipe[child]), address, addr_width);
}else{
write_register(pgm_read_byte(&child_pipe[child]), address, 1);
}
write_register(pgm_read_byte(&child_payload_size[child]),payload_size);
// Note it would be more efficient to set all of the bits for all open
// pipes at once. However, I thought it would make the calling code
// more simple to do it this way.
write_register(EN_RXADDR,read_register(EN_RXADDR) | _BV(pgm_read_byte(&child_pipe_enable[child])));
}
}
/****************************************************************************/
void RF24::closeReadingPipe( uint8_t pipe )
......
......@@ -51,7 +51,8 @@ private:
bool p_variant; /* False for RF24L01 and true for RF24L01P */
uint8_t payload_size; /**< Fixed size of payloads */
bool dynamic_payloads_enabled; /**< Whether dynamic payloads are enabled. */
uint64_t pipe0_reading_address; /**< Last address set on pipe 0 for reading. */
const uint8_t *pipe0_reading_address; /**< Last address set on pipe 0 for reading. */
uint8_t addr_width;
public:
......@@ -163,24 +164,26 @@ public:
bool write( const void* buf, uint8_t len );
/**
* Open a pipe for writing
* New: Open a pipe for writing
*
* Only one pipe can be open at once, but you can change the pipe
* you'll listen to. Do not call this while actively listening.
* Remember to stopListening() first.
* you'll write to. Call stopListening() first.
*
* Addresses are 40-bit hex values, e.g.:
* Addresses are assigned via a byte array, default is 5 byte address length
*
* Usage is exactly the same as before, except for declaring the array
*
* @code
* openWritingPipe(0xF0F0F0F0F0);
* uint8_t addresses[][6] = {"1Node","2Node"};
* openWritingPipe(addresses[0]);
* @endcode
* @see setAddressWidth
*
* @param address The 40-bit address of the pipe to open. This can be
* any value whatsoever, as long as you are the only one writing to it
* and only one other radio is listening to it. Coordinate these pipe
* @param address The address of the pipe to open. Coordinate these pipe
* addresses amongst nodes on the network.
*/
void openWritingPipe(uint64_t address);
void openWritingPipe(const uint8_t *address);
/**
* Open a pipe for reading
......@@ -189,24 +192,25 @@ public:
* reading pipes, and then call startListening().
*
* @see openWritingPipe
* @see setAddressWidth
*
* @warning Pipes 1-5 should share the first 32 bits.
* Only the least significant byte should be unique, e.g.
* @warning Pipes 1-5 should share the same address, except the first byte.
* Only the first byte in the array should be unique, e.g.
* @code
* openReadingPipe(1,0xF0F0F0F0AA);
* openReadingPipe(2,0xF0F0F0F066);
* uint8_t addresses[][6] = {"1Node","2Node"};
* openReadingPipe(1,addresses[0]);
* openReadingPipe(2,addresses[1]);
* @endcode
*
* @warning Pipe 0 is also used by the writing pipe. So if you open
* pipe 0 for reading, and then startListening(), it will overwrite the
* writing pipe. Ergo, do an openWritingPipe() again before write().
*
* @todo Enforce the restriction that pipes 1-5 must share the top 32 bits
*
* @param number Which pipe# to open, 0-5.
* @param address The 40-bit address of the pipe to open.
* @param address The 24, 32 or 40 bit address of the pipe to open.
*/
void openReadingPipe(uint8_t number, uint64_t address);
void openReadingPipe(uint8_t number, const uint8_t *address);
/**
* Close a pipe after it has been previously opened.
......@@ -584,6 +588,14 @@ public:
*/
void maskIRQ(bool tx_ok,bool tx_fail,bool rx_ready);
/**
* Set the address width from 3 to 5 bytes (24, 32 or 40 bit)
*
* @param a_width The address width to use: 3,4 or 5
*/
void setAddressWidth(uint8_t a_width);
/**@}*/
/**@}*/
......@@ -759,6 +771,48 @@ public:
*/
void disableCRC( void ) ;
/**@}*/
/**
* @name Deprecated
*
* Methods provided for backwards compabibility.
*/
/**@{*/
/**
* Open a pipe for reading
* @note For compatibility with old code only, see new function
*
* @warning Pipes 1-5 should share the first 32 bits.
* Only the least significant byte should be unique, e.g.
* @code
* openReadingPipe(1,0xF0F0F0F0AA);
* openReadingPipe(2,0xF0F0F0F066);
* @endcode
*
* @warning Pipe 0 is also used by the writing pipe. So if you open
* pipe 0 for reading, and then startListening(), it will overwrite the
* writing pipe. Ergo, do an openWritingPipe() again before write().
*
* @param number Which pipe# to open, 0-5.
* @param address The 40-bit address of the pipe to open.
*/
void openReadingPipe(uint8_t number, uint64_t address);
/**
* Open a pipe for writing
* @note For compatibility with old code only, see new function
* Addresses are 40-bit hex values, e.g.:
*
* @code
* openWritingPipe(0xF0F0F0F0F0);
* @endcode
*
* @param address The 40-bit address of the pipe to open.
*/
void openWritingPipe(uint64_t address);
private:
/**
......@@ -1085,6 +1139,7 @@ private:
* - Delays have been removed where possible to ensure maximum efficiency
* - Full Due support with extended SPI functions
* - ATTiny 24/44/84 25/45/85 now supported.
* - Raspberry Pi now supported
* - More! See the links below and class documentation for more info.
*
* If issues are discovered with the documentation, please report them here: <a href="https://github.com/TMRh20/tmrh20.github.io/issues"> here</a>
......@@ -1114,6 +1169,7 @@ private:
* Note: ATTiny support is built into the library. Do not include SPI.h. <br>
* ATTiny 85: D0(pin 5): MISO, D1(pin6) MOSI, D2(pin7) SCK, D3(pin2):CSN/SS, D4(pin3): CE <br>
* ATTiny 84: PA6:MISO, PA5:MOSI, PA4:SCK, PA7:CSN/SS, CE as desired <br>
* - Raspberry Pi Support: See the readme at https://github.com/TMRh20/RF24/tree/master/RPi
*
* @section More More Information
*
......
......@@ -265,8 +265,7 @@ void RF24::print_address_register(const char* name, uint8_t reg, uint8_t qty)
RF24::RF24(uint8_t _cepin, uint8_t _cspin, uint32_t _spi_speed):
ce_pin(_cepin), csn_pin(_cspin), spi_speed(_spi_speed), wide_band(true), p_variant(false),
payload_size(32), dynamic_payloads_enabled(false),
pipe0_reading_address(0)
payload_size(32), dynamic_payloads_enabled(false),addr_width(5)//,pipe0_reading_address(0)
{
}
......@@ -477,7 +476,7 @@ bool RF24::begin(void)
toggle_features();
write_register(FEATURE,0 );
write_register(DYNPD,0);
// Reset current status
// Notice reset and flush is the last thing we do
write_register(STATUS,_BV(RX_DR) | _BV(TX_DS) | _BV(MAX_RT) );
......@@ -509,9 +508,9 @@ void RF24::startListening(void)
write_register(STATUS, _BV(RX_DR) | _BV(TX_DS) | _BV(MAX_RT) );
// Restore the pipe0 adddress, if exists
if (pipe0_reading_address)
write_register(RX_ADDR_P0, reinterpret_cast<const uint8_t*>(&pipe0_reading_address), 5);
if (pipe0_reading_address){
write_register(RX_ADDR_P0, pipe0_reading_address, addr_width);
}
// Flush buffers
flush_rx();
flush_tx();
......@@ -805,6 +804,20 @@ void RF24::openWritingPipe(uint64_t value)
write_register(RX_PW_P0,payload_size);
}
/****************************************************************************/
void RF24::openWritingPipe(const uint8_t *address)
{
// Note that AVR 8-bit uC's store this LSB first, and the NRF24L01(+)
// expects it LSB first too, so we're good.
write_register(RX_ADDR_P0,address, addr_width);
write_register(TX_ADDR, address, addr_width);
//const uint8_t max_payload_size = 32;
//write_register(RX_PW_P0,min(payload_size,max_payload_size));
write_register(RX_PW_P0,payload_size);
}
/****************************************************************************/
static const uint8_t child_pipe[] =
......@@ -826,7 +839,7 @@ void RF24::openReadingPipe(uint8_t child, uint64_t address)
// openWritingPipe() will overwrite the pipe 0 address, so
// startListening() will have to restore it.
if (child == 0)
pipe0_reading_address = address;
pipe0_reading_address = reinterpret_cast<uint8_t*>(&address);
if (child <= 6)
{
......@@ -847,6 +860,45 @@ void RF24::openReadingPipe(uint8_t child, uint64_t address)
/****************************************************************************/
void RF24::setAddressWidth(uint8_t a_width){
if(a_width -= 2){
write_register(SETUP_AW,a_width%4);
addr_width = (a_width%4) + 2;
}
}
/****************************************************************************/
void RF24::openReadingPipe(uint8_t child, const uint8_t *address)
{
// If this is pipe 0, cache the address. This is needed because
// openWritingPipe() will overwrite the pipe 0 address, so
// startListening() will have to restore it.
if (child == 0)
pipe0_reading_address = address;
if (child <= 6)
{
// For pipes 2-5, only write the LSB
if ( child < 2 ){
write_register(pgm_read_byte(&child_pipe[child]), address, addr_width);
}else{
write_register(pgm_read_byte(&child_pipe[child]), address, 1);
}
write_register(pgm_read_byte(&child_payload_size[child]),payload_size);
// Note it would be more efficient to set all of the bits for all open
// pipes at once. However, I thought it would make the calling code
// more simple to do it this way.
write_register(EN_RXADDR,read_register(EN_RXADDR) | _BV(pgm_read_byte(&child_pipe_enable[child])));
}
}
/****************************************************************************/
void RF24::toggle_features(void)
{
bcm2835_spi_transfer( ACTIVATE );
......
......@@ -4,11 +4,11 @@
This program is free software; you can redistribute it and/or
modify it under the terms of the GNU General Public License
version 2 as published by the Free Software Foundation.
03/17/2013 : Charles-Henri Hallard (http://hallard.me)
Modified to use with Arduipi board http://hallard.me/arduipi
Modified to use the great bcm2835 library for I/O and SPI
*/
/**
......@@ -54,15 +54,15 @@ class RF24
private:
uint8_t ce_pin; /**< "Chip Enable" pin, activates the RX or TX role */
uint8_t csn_pin; /**< SPI Chip select */
uint16_t spi_speed; /**< SPI Bus Speed */
uint16_t spi_speed; /**< SPI Bus Speed */
bool wide_band; /* 2Mbs data rate in use? */
bool p_variant; /* False for RF24L01 and true for RF24L01P */
uint8_t payload_size; /**< Fixed size of payloads */
//bool ack_payload_available; /**< Whether there is an ack payload waiting */
bool dynamic_payloads_enabled; /**< Whether dynamic payloads are enabled. */
//uint8_t ack_payload_length; /**< Dynamic size of pending ack payload. */
uint64_t pipe0_reading_address; /**< Last address set on pipe 0 for reading. */
//uint32_t spispeed;
bool dynamic_payloads_enabled; /**< Whether dynamic payloads are enabled. */
const uint8_t *pipe0_reading_address; /**< Last address set on pipe 0 for reading. */
uint8_t addr_width;
uint8_t debug ; /* Debug flag */
uint8_t spi_rxbuff[32+1] ; //SPI receive buffer (payload max 32 bytes)
uint8_t spi_txbuff[32+1] ; //SPI transmit buffer (payload max 32 bytes + 1 byte for the command)
......@@ -298,24 +298,26 @@ public:
void read( void* buf, uint8_t len );
/**
* Open a pipe for writing
* New: Open a pipe for writing
*
* Only one pipe can be open at once, but you can change the pipe
* you'll listen to. Do not call this while actively listening.
* Remember to stopListening() first.
* you'll write to. Call stopListening() first.
*
* Addresses are 40-bit hex values, e.g.:
* Addresses are assigned via a byte array, default is 5 byte address length
*
* Usage is exactly the same as before, except for declaring the array
*
* @code
* openWritingPipe(0xF0F0F0F0F0);
* uint8_t addresses[][6] = {"1Node","2Node"};
* openWritingPipe(addresses[0]);
* @endcode
* @see setAddressWidth
*
* @param address The 40-bit address of the pipe to open. This can be
* any value whatsoever, as long as you are the only one writing to it
* and only one other radio is listening to it. Coordinate these pipe
* @param address The address of the pipe to open. Coordinate these pipe
* addresses amongst nodes on the network.
*/
void openWritingPipe(uint64_t address);
void openWritingPipe(const uint8_t *address);
/**
* Open a pipe for reading
......@@ -324,28 +326,29 @@ public:
* reading pipes, and then call startListening().
*
* @see openWritingPipe
* @see setAddressWidth
*
* @warning Pipes 1-5 should share the first 32 bits.
* Only the least significant byte should be unique, e.g.
* @warning Pipes 1-5 should share the same address, except the first byte.
* Only the first byte in the array should be unique, e.g.
* @code
* openReadingPipe(1,0xF0F0F0F0AA);
* openReadingPipe(2,0xF0F0F0F066);
* uint8_t addresses[][6] = {"1Node","2Node"};
* openReadingPipe(1,addresses[0]);
* openReadingPipe(2,addresses[1]);
* @endcode
*
* @warning Pipe 0 is also used by the writing pipe. So if you open
* pipe 0 for reading, and then startListening(), it will overwrite the
* writing pipe. Ergo, do an openWritingPipe() again before write().
*
* @todo Enforce the restriction that pipes 1-5 must share the top 32 bits
*
* @param number Which pipe# to open, 0-5.
* @param address The 40-bit address of the pipe to open.
* @param address The 24, 32 or 40 bit address of the pipe to open.
*/
void openReadingPipe(uint8_t number, uint64_t address);
void openReadingPipe(uint8_t number, const uint8_t *address);
/**@}*/
/**
* @name Optional Configurators
* @name Optional Configurators
*
* Methods you can use to get or set the configuration of the chip.
* None are required. Calling begin() sets up a reasonable set of
......@@ -400,7 +403,7 @@ public:
* @return Payload length of last-received dynamic payload
*/
uint8_t getDynamicPayloadSize(void);
/**
* Enable custom payloads on the acknowledge packets
*
......@@ -480,7 +483,7 @@ public:
* @return true if the change was successful
*/
bool setDataRate(rf24_datarate_e speed);
/**
* Fetches the transmission data rate
*
......@@ -512,9 +515,65 @@ public:
/**@}*/
/**
* @name Advanced Operation
* @name Deprecated
*
* Methods provided for backwards compabibility.
*/
/**@{*/
/**
* Open a pipe for writing
*
* Only one pipe can be open at once, but you can change the pipe
* you'll listen to. Do not call this while actively listening.
* Remember to stopListening() first.
*
* Addresses are 40-bit hex values, e.g.:
*
* @code
* openWritingPipe(0xF0F0F0F0F0);
* @endcode
*
* @param address The 40-bit address of the pipe to open. This can be
* any value whatsoever, as long as you are the only one writing to it
* and only one other radio is listening to it. Coordinate these pipe
* addresses amongst nodes on the network.
*/
void openWritingPipe(uint64_t address);
/**
* Open a pipe for reading
*
* Up to 6 pipes can be open for reading at once. Open all the
* reading pipes, and then call startListening().
*
* @see openWritingPipe
*
* @warning Pipes 1-5 should share the first 32 bits.
* Only the least significant byte should be unique, e.g.
* @code
* openReadingPipe(1,0xF0F0F0F0AA);
* openReadingPipe(2,0xF0F0F0F066);
* @endcode
*
* @warning Pipe 0 is also used by the writing pipe. So if you open
* pipe 0 for reading, and then startListening(), it will overwrite the
* writing pipe. Ergo, do an openWritingPipe() again before write().
*
* @todo Enforce the restriction that pipes 1-5 must share the top 32 bits
*
* @param number Which pipe# to open, 0-5.
* @param address The 40-bit address of the pipe to open.
*/
void openReadingPipe(uint8_t number, uint64_t address);
/**@}*/
/**
* @name Advanced Operation
*
* Methods you can use to drive the chip in more advanced ways
* Methods you can use to drive the chip in more advanced ways
*/
/**@{*/
......@@ -849,7 +908,7 @@ public:
* @return true if this is a legitimate radio
*/
bool isValid() { return ce_pin != 0xff && csn_pin != 0xff; }
/**
* The radio will generate interrupt signals when a transmission is complete,
* a transmission fails, or a payload is received. This allows users to mask
......@@ -868,6 +927,14 @@ public:
*/
void maskIRQ(bool tx_ok,bool tx_fail,bool rx_ready);
/**
* Set the address width from 3 to 5 bytes (24, 32 or 40 bit)
*
* @param a_width The address width to use: 3,4 or 5
*/
void setAddressWidth(uint8_t a_width);
/**@}*/
};
......@@ -875,12 +942,12 @@ public:
* @example GettingStarted.pde
*
* This is an example which corresponds to my "Getting Started" blog post:
* <a style="text-align:center" href="http://maniacbug.wordpress.com/2011/11/02/getting-started-rf24/">Getting Started with nRF24L01+ on Arduino</a>.
* <a style="text-align:center" href="http://maniacbug.wordpress.com/2011/11/02/getting-started-rf24/">Getting Started with nRF24L01+ on Arduino</a>.
*
* It is an example of how to use the RF24 class. Write this sketch to two
* different nodes. Put one of the nodes into 'transmit' mode by connecting
* with the serial monitor and sending a 'T'. The ping node sends the current
* time to the pong node, which responds by sending the value back. The ping
* It is an example of how to use the RF24 class. Write this sketch to two
* different nodes. Put one of the nodes into 'transmit' mode by connecting
* with the serial monitor and sending a 'T'. The ping node sends the current
* time to the pong node, which responds by sending the value back. The ping
* node can then see how long the whole cycle took.
*/
......@@ -912,14 +979,14 @@ public:
*/
/**
* @example pingpair_maple.pde
* @example pingpair_maple.pde
*
* This is an example of how to use the RF24 class on the Maple. For a more
* detailed explanation, see my blog post:
* <a href="http://maniacbug.wordpress.com/2011/12/14/nrf24l01-running-on-maple-3/">nRF24L01+ Running on Maple</a>
*
* It will communicate well to an Arduino-based unit as well, so it's not for only Maple-to-Maple communication.
*
*
* Write this sketch to two different nodes,
* connect the role_pin to ground on one. The ping node sends the current time to the pong node,
* which responds by sending the value back. The ping node can then see how long the whole cycle
......@@ -981,25 +1048,25 @@ public:
* @mainpage Driver for nRF24L01(+) 2.4GHz Wireless Transceiver
*
* @section Goals Design Goals
*
*
* This library is designed to be...
* @li Maximally compliant with the intended operation of the chip
* @li Easy for beginners to use
* @li Consumed with a public interface that's similiar to other Arduino standard libraries
*
* @section News News
*
* NOW COMPATIBLE WITH ARDUINO 1.0 - The 'master' branch and all examples work with both Arduino 1.0 and earlier versions.
*
* NOW COMPATIBLE WITH ARDUINO 1.0 - The 'master' branch and all examples work with both Arduino 1.0 and earlier versions.
* Please <a href="https://github.com/maniacbug/RF24/issues/new">open an issue</a> if you find any problems using it with any version of Arduino.
*
* NOW COMPATIBLE WITH MAPLE - RF24 has been tested with the
* <a href="http://leaflabs.com/store/#Maple-Native">Maple Native</a>,
* NOW COMPATIBLE WITH MAPLE - RF24 has been tested with the
* <a href="http://leaflabs.com/store/#Maple-Native">Maple Native</a>,
* and should work with any Maple board. See the pingpair_maple example.
* Note that only the pingpair_maple example has been tested on Maple, although
* the others can certainly be adapted.
*
* @section Useful Useful References
*
*
* Please refer to:
*
* @li <a href="http://maniacbug.github.com/RF24/">Documentation Main Page</a>
......@@ -1021,11 +1088,11 @@ public:
*
* <img src="http://farm7.staticflickr.com/6044/6307669179_a8d19298a6_m.jpg" width="240" height="160" alt="RF24 Getting Started - Finished Product">
*
* <a style="text-align:center" href="http://maniacbug.wordpress.com/2011/11/02/getting-started-rf24/">Getting Started with nRF24L01+ on Arduino</a>
* <a style="text-align:center" href="http://maniacbug.wordpress.com/2011/11/02/getting-started-rf24/">Getting Started with nRF24L01+ on Arduino</a>
*
* <img src="http://farm8.staticflickr.com/7159/6645514331_38eb2bdeaa_m.jpg" width="240" height="160" alt="Nordic FOB and nRF24L01+">
*
* <a style="text-align:center" href="http://maniacbug.wordpress.com/2012/01/08/nordic-fob/">Using the Sparkfun Nordic FOB</a>
* <a style="text-align:center" href="http://maniacbug.wordpress.com/2012/01/08/nordic-fob/">Using the Sparkfun Nordic FOB</a>
*
* <img src="http://farm7.staticflickr.com/6097/6224308836_b9b3b421a3_m.jpg" width="240" height="160" alt="RF Duinode V3 (2V4)">
*
......
......@@ -44,13 +44,14 @@ RF24 radio(RPI_V2_GPIO_P1_15, RPI_V2_GPIO_P1_24, BCM2835_SPI_SPEED_8MHZ);
// Radio pipe addresses for the 2 nodes to communicate.
const uint64_t pipes[2] = { 0xABCDABCD71LL, 0x544d52687CLL };
const uint8_t pipes[][6] = {"1Node","2Node"};
//const uint64_t pipes[2] = { 0xABCDABCD71LL, 0x544d52687CLL };
bool role_ping_out = 1, role_pong_back = 0;
bool role = 0;
int main(int argc, char** argv){
bool role_ping_out = true, role_pong_back = false;
bool role = role_pong_back;
// Print preamble:
printf("RF24/examples/pingtest/\n");
......@@ -94,7 +95,7 @@ int main(int argc, char** argv){
radio.startListening();
}
// forever loop
while (1)
{
......@@ -144,6 +145,7 @@ int main(int argc, char** argv){
// Try again 1s later
// delay(1000);
sleep(1);
}
......@@ -156,7 +158,7 @@ int main(int argc, char** argv){
{
// if there is data ready
//printf("Check available...\n");
//delay(3);
if ( radio.available() )
{
// Dump the payloads until we've gotten everything
......@@ -167,19 +169,20 @@ int main(int argc, char** argv){
radio.read( &got_time, sizeof(unsigned long) );
radio.stopListening();
//delay(1);
// Seem to need a delay, or the RPi is too quick
radio.write( &got_time, sizeof(unsigned long) );
//delay(1);
// Now, resume listening so we catch the next packets.
radio.startListening();
//delay(1);
// Spew it
printf("Got payload(%d) %lu...\n",sizeof(unsigned long), got_time);
}
//delay(5);
}
} // forever loop
return 0;
......
......@@ -38,7 +38,7 @@ RF24 radio(RPI_V2_GPIO_P1_15, RPI_V2_GPIO_P1_24, BCM2835_SPI_SPEED_8MHZ);
// Radio pipe addresses for the 2 nodes to communicate.
const uint64_t addresses[2] = { 0xABCDABCD71LL, 0x544d52687CLL };
const uint8_t addresses[][6] = {"1Node","2Node"};
bool role_ping_out = 1, role_pong_back = 0, role = 0;
......
......@@ -35,8 +35,7 @@ RF24 radio(RPI_V2_GPIO_P1_15, RPI_V2_GPIO_P1_24, BCM2835_SPI_SPEED_8MHZ);
// Radio pipe addresses for the 2 nodes to communicate.
const uint64_t pipes[2] = { 0xF0F0F0F0E1LL, 0xF0F0F0F0D2LL };
bool role_ping_out = 1, role_pong_back = 0;
bool role = 0;
const int min_payload_size = 4;
const int max_payload_size = 32;
......@@ -47,6 +46,8 @@ char receive_payload[max_payload_size+1]; // +1 to allow room for a terminating
int main(int argc, char** argv){
bool role_ping_out = 1, role_pong_back = 0;
bool role = 0;
// Print preamble:
printf("RF24/examples/pingpair_dyn/\n");
......
......@@ -40,13 +40,14 @@ RF24 radio(RPI_V2_GPIO_P1_15, RPI_V2_GPIO_P1_24, BCM2835_SPI_SPEED_8MHZ);
// Radio pipe addresses for the 2 nodes to communicate.
const uint64_t addresses[2] = { 0xABCDABCD71LL, 0x544d52687CLL };
bool role_ping_out = 1, role_pong_back = 0;
bool role = 0;
uint8_t data[32];
unsigned long startTime, stopTime, counter, rxTimer=0;
int main(int argc, char** argv){
bool role_ping_out = 1, role_pong_back = 0;
bool role = 0;
// Print preamble:
......
......@@ -27,7 +27,8 @@
// Hardware configuration: Set up nRF24L01 radio on SPI bus plus pins 9 & 10
RF24 radio(7,8);
const uint64_t addresses[2] = { 0xABCDABCD71LL, 0x544d52687CLL }; // Radio pipe addresses for the 2 nodes to communicate.
byte addresses[][6] = {"1Node","2Node"};
// Set up roles to simplify testing
boolean role; // The main role variable, holds the current role identifier
......@@ -45,10 +46,9 @@ void setup() {
radio.begin(); // Start up the radio
radio.setAutoAck(1); // Ensure autoACK is enabled
radio.setRetries(15,15); // Max delay between retries & number of retries
radio.openWritingPipe(addresses[1]);
radio.openReadingPipe(1,addresses[0]);
radio.openWritingPipe(addresses[1]); // Open a writing pipe on pipe 0, with address 1
radio.openReadingPipe(1,addresses[0]); // Open a reading pipe on pipe 1, with address 0
radio.startListening(); // Start listening
radio.printDetails(); // Dump the configuration of the rf unit for debugging
}
......@@ -123,6 +123,7 @@ void loop(void){
role = role_ping_out; // Become the primary transmitter (ping out)
radio.openWritingPipe(addresses[0]);
radio.openReadingPipe(1,addresses[1]);
}
else if ( c == 'R' && role == role_ping_out )
{
......
......@@ -20,7 +20,7 @@
// Hardware configuration: Set up nRF24L01 radio on SPI bus plus pins 9 & 10
RF24 radio(7,8);
// Topology
const uint64_t addresses[2] = { 0xABCDABCD71LL, 0x544d52687CLL }; // Radio pipe addresses for the 2 nodes to communicate.
byte addresses[][6] = {"1Node","2Node"}; // Radio pipe addresses for the 2 nodes to communicate.
// Role management: Set up role. This sketch uses the same software for all the nodes
// in this system. Doing so greatly simplifies testing.
......
Markdown is supported
0%
or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment