first commit

This commit is contained in:
Lazarewicz Julien
2025-07-22 15:27:00 +02:00
commit 6c6451c92c
205 changed files with 44418 additions and 0 deletions

View File

@@ -0,0 +1,102 @@
// abz_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple messageing client
// with the RH_ABZ class. RH_ABZ class does not provide for addressing or
// reliability, so you should only use RH_ABZ directly if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example abz_server
// Tested with Tested with EcoNode SmartTrap, Arduino 1.8.9, GrumpyOldPizza Arduino Core for STM32L0.
#include <SPI.h>
#include <RH_ABZ.h>
// Singleton instance of the radio driver
RH_ABZ abz;
// Valid for SmartTrap, maybe not other boards
#define GREEN_LED 13
#define YELLOW_LED 12
#define RED_LED 11
void setup()
{
pinMode(GREEN_LED, OUTPUT);
pinMode(YELLOW_LED, OUTPUT);
pinMode(RED_LED, OUTPUT);
Serial.begin(9600);
// Wait for serial port to be available
// If you do this, it will block here until a USB serial connection is made.
// If not, it will continue without a Serial connection, but DFU mode will not be available
// to the host without resetting the CPU with the Boot button
// while (!Serial) ;
// You must be sure that the TCXO settings are appropriate for your board and radio.
// See the RH_ABZ documentation for more information.
// This call is adequate for Tlera boards supported by the Grumpy Old Pizza Arduino Core
// It may or may not be innocuous for others
SX1276SetBoardTcxo(true);
delay(1);
if (!abz.init())
Serial.println("init failed");
// Defaults after init are 434.0MHz, 13dBm, Bw = 125 kHz, Cr = 4/5, Sf = 128chips/symbol, CRC on
abz.setFrequency(868.0);
// You can change the modulation speed etc from the default
//abz.setModemConfig(RH_RF95::Bw125Cr45Sf128);
//abz.setModemConfig(RH_RF95::Bw125Cr45Sf2048);
// The default transmitter power is 13dBm, using PA_BOOST.
// You can set transmitter powers from 2 to 20 dBm:
//abz.setTxPower(20); // Max power
}
void loop()
{
digitalWrite(YELLOW_LED, 1);
digitalWrite(GREEN_LED, 0);
digitalWrite(RED_LED, 0);
Serial.println("Sending to abz_server");
// Send a message to abz_server
uint8_t data[] = "Hello World!";
abz.send(data, sizeof(data));
abz.waitPacketSent();
// Now wait for a reply
uint8_t buf[RH_RF95_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
// You might need a longer timeout for slow modulatiuon schemes and/or long messages
if (abz.waitAvailableTimeout(3000))
{
// Should be a reply message for us now
if (abz.recv(buf, &len))
{
Serial.print("got reply: ");
Serial.println((char*)buf);
// Serial.print("RSSI: ");
// Serial.println(abz.lastRssi(), DEC);
digitalWrite(GREEN_LED, 1);
}
else
{
Serial.println("recv failed");
digitalWrite(RED_LED, 1);
}
}
else
{
Serial.println("No reply, is abz_server running?");
digitalWrite(RED_LED, 1);
}
digitalWrite(YELLOW_LED, 0);
delay(400);
}

View File

@@ -0,0 +1,90 @@
// abz_server.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple messageing server
// with the RH_ABZ class. RH_ABZ class does not provide for addressing or
// reliability, so you should only use RH_ABZ directly if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example abz_server
// Tested with Tested with EcoNode SmartTrap, Arduino 1.8.9, GrumpyOldPizza Arduino Core for STM32L0.
#include <SPI.h>
#include <RH_ABZ.h>
// Singleton instance of the radio driver
RH_ABZ abz;
// Valid for SmartTrap, maybe not other boards
#define GREEN_LED 13
#define YELLOW_LED 12
#define RED_LED 11
void setup()
{
pinMode(GREEN_LED, OUTPUT);
pinMode(YELLOW_LED, OUTPUT);
pinMode(RED_LED, OUTPUT);
Serial.begin(9600);
// Wait for serial port to be available
// If you do this, it will block here until a USB serial connection is made.
// If not, it will continue without a Serial connection, but DFU mode will not be available
// to the host without resetting the CPU with the Boot button
// while (!Serial) ;
// You must be sure that the TCXO settings are appropriate for your board and radio.
// See the RH_ABZ documentation for more information.
// This call is adequate for Tlera boards supported by the Grumpy Old Pizza Arduino Core
// It may or may not be innocuous for others
SX1276SetBoardTcxo(true);
delay(1);
if (!abz.init())
Serial.println("init failed");
// Defaults after init are 434.0MHz, 13dBm, Bw = 125 kHz, Cr = 4/5, Sf = 128chips/symbol, CRC on
abz.setFrequency(868.0);
// You can change the modulation speed etc from the default
//abz.setModemConfig(RH_RF95::Bw125Cr45Sf128);
//abz.setModemConfig(RH_RF95::Bw125Cr45Sf2048);
// The default transmitter power is 13dBm, using PA_BOOST.
// You can set transmitter powers from 2 to 20 dBm:
//abz.setTxPower(20); // Max power
}
void loop()
{
digitalWrite(YELLOW_LED, 1);
digitalWrite(GREEN_LED, 0);
digitalWrite(RED_LED, 0);
if (abz.available())
{
// Should be a message for us now
uint8_t buf[RH_RF95_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (abz.recv(buf, &len))
{
digitalWrite(GREEN_LED, 1);
// RH_ABZ::printBuffer("request: ", buf, len);
Serial.print("got request: ");
Serial.println((char*)buf);
// Serial.print("RSSI: ");
// Serial.println(abz.lastRssi(), DEC);
// Send a reply
uint8_t data[] = "And hello back to you";
abz.send(data, sizeof(data));
abz.waitPacketSent();
Serial.println("Sent a reply");
digitalWrite(GREEN_LED, 0);
}
else
{
Serial.println("recv failed");
}
}
}

View File

@@ -0,0 +1,43 @@
// ask_receiver.pde
// -*- mode: C++ -*-
// Simple example of how to use RadioHead to receive messages
// with a simple ASK transmitter in a very simple way.
// Implements a simplex (one-way) receiver with an Rx-B1 module
// Tested on Arduino Mega, Duemilanova, Uno, Due, Teensy, ESP-12
#include <RH_ASK.h>
#ifdef RH_HAVE_HARDWARE_SPI
#include <SPI.h> // Not actually used but needed to compile
#endif
RH_ASK driver;
// RH_ASK driver(2000, 4, 5, 0); // ESP8266 or ESP32: do not use pin 11 or 2
// RH_ASK driver(2000, 3, 4, 0); // ATTiny, RX on D3 (pin 2 on attiny85) TX on D4 (pin 3 on attiny85),
// RH_ASK driver(2000, PD14, PD13, 0); STM32F4 Discovery: see tx and rx on Orange and Red LEDS
void setup()
{
#ifdef RH_HAVE_SERIAL
Serial.begin(9600); // Debugging only
#endif
if (!driver.init())
#ifdef RH_HAVE_SERIAL
Serial.println("init failed");
#else
;
#endif
}
void loop()
{
uint8_t buf[RH_ASK_MAX_MESSAGE_LEN];
uint8_t buflen = sizeof(buf);
if (driver.recv(buf, &buflen)) // Non-blocking
{
int i;
// Message with a good checksum received, dump it.
driver.printBuffer("Got:", buf, buflen);
}
}

View File

@@ -0,0 +1,60 @@
// ask_reliable_datagram_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, reliable messaging client
// with the RHReliableDatagram class, using the RH_ASK driver to control a ASK radio.
// It is designed to work with the other example ask_reliable_datagram_server
// Tested on Arduino Mega, Duemilanova, Uno, Due, Teensy, ESP-12
#include <RHReliableDatagram.h>
#include <RH_ASK.h>
#include <SPI.h>
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
// Singleton instance of the radio driver
RH_ASK driver;
// RH_ASK driver(2000, 4, 5, 0); // ESP8266 or ESP32: do not use pin 11 or 2
// RH_ASK driver(2000, PD14, PD13, 0); STM32F4 Discovery: see tx and rx on Orange and Red LEDS
// Class to manage message delivery and receipt, using the driver declared above
RHReliableDatagram manager(driver, CLIENT_ADDRESS);
void setup()
{
Serial.begin(9600);
if (!manager.init())
Serial.println("init failed");
}
uint8_t data[] = "Hello World!";
// Dont put this on the stack:
uint8_t buf[RH_ASK_MAX_MESSAGE_LEN];
void loop()
{
Serial.println("Sending to ask_reliable_datagram_server");
// Send a message to manager_server
if (manager.sendtoWait(data, sizeof(data), SERVER_ADDRESS))
{
// Now wait for a reply from the server
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAckTimeout(buf, &len, 2000, &from))
{
Serial.print("got reply from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
}
else
{
Serial.println("No reply, is ask_reliable_datagram_server running?");
}
}
else
Serial.println("sendtoWait failed");
delay(500);
}

View File

@@ -0,0 +1,54 @@
// ask_reliable_datagram_server.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, reliable messaging server
// with the RHReliableDatagram class, using the RH_ASK driver to control a ASK radio.
// It is designed to work with the other example ask_reliable_datagram_client
// Tested on Arduino Mega, Duemilanova, Uno, Due, Teensy, ESP-12
#include <RHReliableDatagram.h>
#include <RH_ASK.h>
#include <SPI.h>
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
// Singleton instance of the radio driver
RH_ASK driver;
// RH_ASK driver(2000, 4, 5, 0); // ESP8266 or ESP32: do not use pin 11 or 2
// RH_ASK driver(2000, PD14, PD13, 0); STM32F4 Discovery: see tx and rx on Orange and Red LEDS
// Class to manage message delivery and receipt, using the driver declared above
RHReliableDatagram manager(driver, SERVER_ADDRESS);
void setup()
{
Serial.begin(9600);
if (!manager.init())
Serial.println("init failed");
}
uint8_t data[] = "And hello back to you";
// Dont put this on the stack:
uint8_t buf[RH_ASK_MAX_MESSAGE_LEN];
void loop()
{
if (manager.available())
{
// Wait for a message addressed to us from the client
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
// Send a reply back to the originator client
if (!manager.sendtoWait(data, sizeof(data), from))
Serial.println("sendtoWait failed");
}
}
}

View File

@@ -0,0 +1,38 @@
// ask_transmitter.pde
// -*- mode: C++ -*-
// Simple example of how to use RadioHead to transmit messages
// with a simple ASK transmitter in a very simple way.
// Implements a simplex (one-way) transmitter with an TX-C1 module
// Tested on Arduino Mega, Duemilanova, Uno, Due, Teensy, ESP-12
#include <RH_ASK.h>
#ifdef RH_HAVE_HARDWARE_SPI
#include <SPI.h> // Not actually used but needed to compile
#endif
RH_ASK driver;
// RH_ASK driver(2000, 4, 5, 0); // ESP8266 or ESP32: do not use pin 11 or 2
// RH_ASK driver(2000, 3, 4, 0); // ATTiny, RX on D3 (pin 2 on attiny85) TX on D4 (pin 3 on attiny85),
// RH_ASK driver(2000, PD14, PD13, 0); STM32F4 Discovery: see tx and rx on Orange and Red LEDS
void setup()
{
#ifdef RH_HAVE_SERIAL
Serial.begin(9600); // Debugging only
#endif
if (!driver.init())
#ifdef RH_HAVE_SERIAL
Serial.println("init failed");
#else
;
#endif
}
void loop()
{
const char *msg = "hello";
driver.send((uint8_t *)msg, strlen(msg));
driver.waitPacketSent();
delay(200);
}

View File

@@ -0,0 +1,75 @@
// cc110_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple messageing client
// with the RH_CC110 class. RH_CC110 class does not provide for addressing or
// reliability, so you should only use RH_CC110 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example cc110_server
// Tested with Teensy 3.1 and Anaren 430BOOST-CC110L
#include <SPI.h>
#include <RH_CC110.h>
// Singleton instance of the radio driver
RH_CC110 cc110;
void setup()
{
Serial.begin(9600);
while (!Serial)
; // wait for serial port to connect. Needed for native USB
// CC110L may be equipped with either 26 or 27MHz crystals. You MUST
// tell the driver if a 27MHz crystal is installed for the correct configuration to
// occur. Failure to correctly set this flag will cause incorrect frequency and modulation
// characteristics to be used. You can call this function, or pass it to the constructor
cc110.setIs27MHz(true); // Anaren 430BOOST-CC110L Air BoosterPack test boards have 27MHz
if (!cc110.init())
Serial.println("init failed");
// After init(), the following default values apply:
// TxPower: TransmitPower5dBm
// Frequency: 915.0
// Modulation: GFSK_Rb1_2Fd5_2 (GFSK, Data Rate: 1.2kBaud, Dev: 5.2kHz, RX BW 58kHz, optimised for sensitivity)
// Sync Words: 0xd3, 0x91
// But you can change them:
// cc110.setTxPower(RH_CC110::TransmitPowerM30dBm);
// cc110.setModemConfig(RH_CC110::GFSK_Rb250Fd127);
//cc110.setFrequency(928.0);
}
void loop()
{
Serial.println("Sending to cc110_server");
// Send a message to cc110_server
uint8_t data[] = "Hello World!";
cc110.send(data, sizeof(data));
cc110.waitPacketSent();
// Now wait for a reply
uint8_t buf[RH_CC110_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (cc110.waitAvailableTimeout(3000))
{
// Should be a reply message for us now
if (cc110.recv(buf, &len))
{
Serial.print("got reply: ");
Serial.println((char*)buf);
// Serial.print("RSSI: ");
// Serial.println(cc110.lastRssi(), DEC);
}
else
{
Serial.println("recv failed");
}
}
else
{
Serial.println("No reply, is cc110_server running?");
}
delay(400);
}

View File

@@ -0,0 +1,69 @@
// cc110_server.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple messageing server
// with the RH_CC110 class. RH_CC110 class does not provide for addressing or
// reliability, so you should only use RH_CC110 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example cc110_client
// Tested with Teensy 3.1 and Anaren 430BOOST-CC110L
#include <SPI.h>
#include <RH_CC110.h>
// Singleton instance of the radio driver
RH_CC110 cc110;
void setup()
{
Serial.begin(9600);
while (!Serial)
; // wait for serial port to connect. Needed for native USB
// CC110L may be equipped with either 26 or 27MHz crystals. You MUST
// tell the driver if a 27MHz crystal is installed for the correct configuration to
// occur. Failure to correctly set this flag will cause incorrect frequency and modulation
// characteristics to be used. You can call this function, or pass it to the constructor
cc110.setIs27MHz(true); // Anaren 430BOOST-CC110L Air BoosterPack test boards have 27MHz
if (!cc110.init())
Serial.println("init failed");
// After init(), the following default values apply:
// TxPower: TransmitPower5dBm
// Frequency: 915.0
// Modulation: GFSK_Rb1_2Fd5_2 (GFSK, Data Rate: 1.2kBaud, Dev: 5.2kHz, RX BW 58kHz, optimised for sensitivity)
// Sync Words: 0xd3, 0x91
// But you can change them:
// cc110.setTxPower(RH_CC110::TransmitPowerM30dBm);
// cc110.setModemConfig(RH_CC110::GFSK_Rb250Fd127);
//cc110.setFrequency(928.0);
}
void loop()
{
if (cc110.available())
{
// Should be a message for us now
uint8_t buf[RH_CC110_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (cc110.recv(buf, &len))
{
// RH_CC110::printBuffer("request: ", buf, len);
Serial.print("got request: ");
Serial.println((char*)buf);
// Serial.print("RSSI: ");
// Serial.println(cc110.lastRssi(), DEC);
// Send a reply
uint8_t data[] = "And hello back to you";
cc110.send(data, sizeof(data));
cc110.waitPacketSent();
Serial.println("Sent a reply");
}
else
{
Serial.println("recv failed");
}
}
}

View File

@@ -0,0 +1,70 @@
// e32_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple messageing client
// with the RH_E32 class. RH_E32 class does not provide for addressing or
// reliability, so you should only use RH_E32 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example e32_server
// Tested on Uno with E32-TTL-1W
#include <RH_E32.h>
#include "SoftwareSerial.h"
SoftwareSerial mySerial(7, 6);
RH_E32 driver(&mySerial, 4, 5, 8);
void setup()
{
Serial.begin(9600);
while (!Serial) ; // Wait for serial port to be available
// Init the serial connection to the E32 module
// which is assumned to be running at 9600baud.
// If your E32 has been configured to another baud rate, change this:
mySerial.begin(9600);
while (!mySerial) ;
if (!driver.init())
Serial.println("init failed");
// Defaults after initialising are:
// 433MHz, 21dBm, 5kbps
// You can change these as below
// if (!driver.setDataRate(RH_E32::DataRate1kbps))
// Serial.println("setDataRate failed");
// if (!driver.setPower(RH_E32::Power30dBm))
// Serial.println("setPower failed");
// if (!driver.setFrequency(434))
// Serial.println("setFrequency failed");
}
void loop()
{
Serial.println("Sending to e32_server");
// Send a message to e32_server
uint8_t data[] = "Hello World!";
driver.send(data, sizeof(data));
driver.waitPacketSent();
// Now wait for a reply
uint8_t buf[RH_E32_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (driver.waitAvailableTimeout(10000)) // At 1kbps, reply can take a long time
{
// Should be a reply message for us now
if (driver.recv(buf, &len))
{
Serial.print("got reply: ");
Serial.println((char*)buf);
}
else
{
Serial.println("recv failed");
}
}
else
{
Serial.println("No reply, is e32_server running?");
}
delay(1000);
}

View File

@@ -0,0 +1,64 @@
// e32_server.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple messageing client
// with the RH_E32 class. RH_E32 class does not provide for addressing or
// reliability, so you should only use RH_E32 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example e32_client
// Tested on Uno with E32-TTL-1W
#include <RH_E32.h>
#include "SoftwareSerial.h"
SoftwareSerial mySerial(7, 6);
RH_E32 driver(&mySerial, 4, 5, 8);
void setup()
{
Serial.begin(9600);
while (!Serial) ; // Wait for serial port to be available
// Init the serial connection to the E32 module
// which is assumned to be running at 9600baud.
// If your E32 has been configured to another baud rate, change this:
mySerial.begin(9600);
while (!mySerial) ;
if (!driver.init())
Serial.println("init failed");
// Defaults after initialising are:
// 433MHz, 21dBm, 5kbps
// You can change these as below
// if (!driver.setDataRate(RH_E32::DataRate1kbps))
// Serial.println("setDataRate failed");
// if (!driver.setPower(RH_E32::Power30dBm))
// Serial.println("setPower failed");
// if (!driver.setFrequency(434))
// Serial.println("setFrequency failed");
}
void loop()
{
if (driver.available())
{
// Should be a message for us now
uint8_t buf[RH_E32_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (driver.recv(buf, &len))
{
// RH_E32::printBuffer("request: ", buf, len);
Serial.print("got request: ");
Serial.println((char*)buf);
// Send a reply
uint8_t data[] = "And hello back to you";
driver.send(data, sizeof(data));
driver.waitPacketSent();
Serial.println("Sent a reply");
}
else
{
Serial.println("recv failed");
}
}
}

View File

@@ -0,0 +1,81 @@
// lorafileops_client.cpp
// -*- mode: C++ -*-
//
// Example program demonstrating how to use
// RH_LoRaFileOps driver on RPi+Linux with a radio supported by
// the LoRa-file-ops Linix driver, such as the SX1278.
// See See https://github.com/starnight/LoRa/tree/file-ops
//
// You can build this in the top level RadioHead directory with something like:
// cd RadioHead
// g++ -o lorafileops_client -I . RH_LoRaFileOps.cpp RHGenericDriver.cpp tools/simMain.cpp examples/lorafileops/lorafileops_client/lorafileops_client.cpp
//
// And run with
// sudo ./lorafileops_client
// (root needed to open /dev/loraSPI0.0
//
// Ensure a RadioHead LoRa compatible receiver is running
// with modem config RH_RF95::Bw125Cr45Sf2048
// eg examples/rf95/rf95_server/rf95_server.pde
// or
// examples/lorafileops/lorafileops_server/lorafileops_server.cpp
#include <RH_LoRaFileOps.h>
// An instance of the RadioHead LoraFileOps driver
RH_LoRaFileOps lora("/dev/loraSPI0.0");
void setup()
{
if (!lora.init())
Serial.println("init failed");
// Defaults after init are:
// Centre frequency 434.0 MHz
// 13dBm transmit power
// Bandwidth 125kHz
// Spreading Factor 2045
// CRC on
// But you can change them all:
//lora.setFrequency(434000000);
lora.setTxPower(17);
//lora.setSpreadingFactor(1024);
//lora.setLNA(10);
//lora.setBW(250000);
}
void loop()
{
Serial.println("Sending to server");
uint8_t data[] = "Hello World!";
lora.send(data, sizeof(data));
lora.waitPacketSent();
// Now wait for a reply
uint8_t buf[RH_LORAFILEOPS_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (lora.waitAvailableTimeout(6000, 100))
{
// Should be a reply message for us now
if (lora.recv(buf, &len))
{
Serial.print("got reply: ");
Serial.println((char*)buf);
Serial.print("RSSI: ");
Serial.println(lora.lastRssi(), DEC);
Serial.print("SNR: ");
Serial.println(lora.lastSNR(), DEC);
}
else
{
Serial.println("recv failed");
}
}
else
{
Serial.println("No reply, is server running?");
}
delay(1000);
}

View File

@@ -0,0 +1,73 @@
// lorafileops_server.cpp
// -*- mode: C++ -*-
//
// Example program demonstrating how to use
// RH_LoRaFileOps driver on RPi+Linux with a radio supported by
// the LoRa-file-ops Linix driver, such as the SX1278.
// See See https://github.com/starnight/LoRa/tree/file-ops
//
// You can build this in the top level RadioHead directory with something like:
// cd RadioHead
// g++ -o lorafileops_server -I . RH_LoRaFileOps.cpp RHGenericDriver.cpp tools/simMain.cpp examples/lorafileops/lorafileops_server/lorafileops_server.cpp
//
// And run with
// sudo ./lorafileops_server
// (root needed to open /dev/loraSPI0.0
//
// Ensure a RadioHead LoRa compatible transmitter is running
// with modem config RH_RF95::Bw125Cr45Sf2048
// eg examples/rf95/rf95_client/rf95_client.pde
// or
// examples/lorafileops/lorafileops_client/lorafileops_client.cpp
#include <RH_LoRaFileOps.h>
// An instance of the RadioHead LoraFileOps driver
RH_LoRaFileOps lora("/dev/loraSPI0.0");
void setup()
{
if (!lora.init())
Serial.println("init failed");
// Defaults after init are:
// Centre frequency 434.0 MHz
// 13dBm transmit power
// Bandwidth 125kHz
// Spreading Factor 2045
// CRC on
// But you can change them all:
//lora.setFrequency(434000000);
lora.setTxPower(17);
//lora.setSpreadingFactor(1024);
//lora.setLNA(10);
//lora.setBW(250000);
}
void loop()
{
lora.waitAvailable(100);
// Should be a message for us now
uint8_t buf[RH_LORAFILEOPS_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (lora.recv(buf, &len))
{
RH_LoRaFileOps::printBuffer("request: ", buf, len);
Serial.print("got request: ");
Serial.println((char*)buf);
Serial.print("RSSI: ");
Serial.println(lora.lastRssi(), DEC);
// Send a reply
uint8_t data[] = "And hello back to you";
lora.send(data, sizeof(data)); // Returns when packet fully transmitted
Serial.println("Sent a reply");
}
else
{
Serial.println("recv failed");
}
}

View File

@@ -0,0 +1,68 @@
// mrf89_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple messageing client
// with the RH_MRF89 class. RH_MRF89 class does not provide for addressing or
// reliability, so you should only use RH_RF95 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example mrf89_server
// Tested with Teensy and MRF89XAM9A
#include <SPI.h>
#include <RH_MRF89.h>
// Singleton instance of the radio driver
RH_MRF89 mrf89;
void setup()
{
Serial.begin(9600);
while (!Serial)
; // wait for serial port to connect. Needed for native USB
if (!mrf89.init())
Serial.println("init failed");
// Default after init is 1dBm, 915.4MHz, FSK_Rb20Fd40
// But you can change that if you want:
// mrf89.setTxPower(RH_MRF89_TXOPVAL_M8DBM); // Min power -8dBm
// mrf89.setTxPower(RH_MRF89_TXOPVAL_13DBM); // Max power 13dBm
// if (!mrf89.setFrequency(920.0))
// Serial.println("setFrequency failed");
// if (!mrf89.setModemConfig(RH_MRF89::FSK_Rb200Fd200)) // Fastest
// Serial.println("setModemConfig failed");
}
void loop()
{
Serial.println("Sending to mrf89_server");
// Send a message to mrf89_server
uint8_t data[] = "Hello World!";
mrf89.send(data, sizeof(data));
mrf89.waitPacketSent();
// Now wait for a reply
uint8_t buf[RH_MRF89_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (mrf89.waitAvailableTimeout(3000))
{
// Should be a reply message for us now
if (mrf89.recv(buf, &len))
{
Serial.print("got reply: ");
Serial.println((char*)buf);
// Serial.print("RSSI: ");
// Serial.println(mrf89.lastRssi(), DEC);
}
else
{
Serial.println("recv failed");
}
}
else
{
Serial.println("No reply, is mrf89_server running?");
}
delay(400);
}

View File

@@ -0,0 +1,67 @@
// mrf89_server.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple messageing server
// with the RH_MRF89 class. RH_MRF89 class does not provide for addressing or
// reliability, so you should only use RH_MRF89 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example mrf89_client
// Tested with Teensy and MRF89XAM9A
#include <SPI.h>
#include <RH_MRF89.h>
// Singleton instance of the radio driver
RH_MRF89 mrf89;
void setup()
{
Serial.begin(9600);
while (!Serial)
; // wait for serial port to connect. Needed for native USB
if (!mrf89.init())
Serial.println("init failed");
// Default after init is 1dBm, 915.4MHz, FSK_Rb20Fd40
// But you can change that if you want:
// mrf89.setTxPower(RH_MRF89_TXOPVAL_M8DBM); // Min power -8dBm
// mrf89.setTxPower(RH_MRF89_TXOPVAL_13DBM); // Max power 13dBm
// if (!mrf89.setFrequency(920.0))
// Serial.println("setFrequency failed");
// if (!mrf89.setModemConfig(RH_MRF89::FSK_Rb200Fd200)) // Fastest
// Serial.println("setModemConfig failed");
}
void loop()
{
if (mrf89.available())
{
// Should be a message for us now
uint8_t buf[RH_MRF89_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (mrf89.recv(buf, &len))
{
// RH_MRF89::printBuffer("request: ", buf, len);
Serial.print("got request: ");
Serial.println((char*)buf);
// Serial.print("RSSI: ");
// Serial.println(mrf89.lastRssi(), DEC);
// Send a reply
uint8_t data[] = "And hello back to you";
mrf89.send(data, sizeof(data));
mrf89.waitPacketSent();
Serial.println("Sent a reply");
}
else
{
Serial.println("recv failed");
}
}
// delay(10000);
// mrf89.printRegisters();
// while (1);
}

View File

@@ -0,0 +1,67 @@
// nrf24_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple messageing client
// with the RH_NRF24 class. RH_NRF24 class does not provide for addressing or
// reliability, so you should only use RH_NRF24 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example nrf24_server.
// Tested on Uno with Sparkfun NRF25L01 module
// Tested on Anarduino Mini (http://www.anarduino.com/mini/) with RFM73 module
// Tested on Arduino Mega with Sparkfun WRL-00691 NRF25L01 module
#include <SPI.h>
#include <RH_NRF24.h>
// Singleton instance of the radio driver
RH_NRF24 nrf24;
// RH_NRF24 nrf24(8, 7); // use this to be electrically compatible with Mirf
// RH_NRF24 nrf24(8, 10);// For Leonardo, need explicit SS pin
// RH_NRF24 nrf24(8, 7); // For RFM73 on Anarduino Mini
void setup()
{
Serial.begin(9600);
while (!Serial)
; // wait for serial port to connect. Needed for Leonardo only
if (!nrf24.init())
Serial.println("init failed");
// Defaults after init are 2.402 GHz (channel 2), 2Mbps, 0dBm
if (!nrf24.setChannel(1))
Serial.println("setChannel failed");
if (!nrf24.setRF(RH_NRF24::DataRate2Mbps, RH_NRF24::TransmitPower0dBm))
Serial.println("setRF failed");
}
void loop()
{
Serial.println("Sending to nrf24_server");
// Send a message to nrf24_server
uint8_t data[] = "Hello World!";
nrf24.send(data, sizeof(data));
nrf24.waitPacketSent();
// Now wait for a reply
uint8_t buf[RH_NRF24_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (nrf24.waitAvailableTimeout(500))
{
// Should be a reply message for us now
if (nrf24.recv(buf, &len))
{
Serial.print("got reply: ");
Serial.println((char*)buf);
}
else
{
Serial.println("recv failed");
}
}
else
{
Serial.println("No reply, is nrf24_server running?");
}
delay(400);
}

View File

@@ -0,0 +1,78 @@
// nrf24_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple encrypted messageing client
// with the RH_NRF24 class. RH_NRF24 class does not provide for addressing or
// reliability, so you should only use RH_NRF24 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example nrf24_encrypted_server.
// Tested on Duemilanove with Sparkfun NRF25L01 module
#include <SPI.h>
#include <RH_NRF24.h>
#include <RHEncryptedDriver.h>
#include <Speck.h>
// Singleton instance of the radio driver
RH_NRF24 nrf24;
// RH_NRF24 nrf24(8, 7); // use this to be electrically compatible with Mirf
// RH_NRF24 nrf24(8, 10);// For Leonardo, need explicit SS pin
// RH_NRF24 nrf24(8, 7); // For RFM73 on Anarduino Mini
// You can choose any of several encryption ciphers
Speck myCipher; // Instantiate a Speck block ciphering
// The RHEncryptedDriver acts as a wrapper for the actual radio driver
RHEncryptedDriver driver(nrf24, myCipher);
// The key MUST be the same as the one in the server
unsigned char encryptkey[16] = {1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16};
void setup()
{
Serial.begin(9600);
while (!Serial)
; // wait for serial port to connect. Needed for Leonardo only
if (!nrf24.init())
Serial.println("init failed");
// Defaults after init are 2.402 GHz (channel 2), 2Mbps, 0dBm
if (!nrf24.setChannel(1))
Serial.println("setChannel failed");
if (!nrf24.setRF(RH_NRF24::DataRate2Mbps, RH_NRF24::TransmitPower0dBm))
Serial.println("setRF failed");
// Now set up the encryption key in our cipher
myCipher.setKey(encryptkey, sizeof(encryptkey));
}
void loop()
{
Serial.println("Sending to nrf24_encrypted_server");
// Send a message to nrf24_server
uint8_t data[] = "Hello World!"; // Dont make this too long
driver.send(data, sizeof(data));
driver.waitPacketSent();
// Now wait for a reply
uint8_t buf[RH_NRF24_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (driver.waitAvailableTimeout(500))
{
// Should be a reply message for us now
if (driver.recv(buf, &len))
{
Serial.print("got reply: ");
Serial.println((char*)buf);
}
else
{
Serial.println("recv failed");
}
}
else
{
Serial.println("No reply, is nrf24_encrypted_server running?");
}
delay(400);
}

View File

@@ -0,0 +1,69 @@
// nrf24_server.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple encrypted messageing server
// with the RH_NRF24 class. RH_NRF24 class does not provide for addressing or
// reliability, so you should only use RH_NRF24 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example nrf24_encrypted_client
#include <SPI.h>
#include <RH_NRF24.h>
#include <RHEncryptedDriver.h>
#include <Speck.h>
// Singleton instance of the radio driver
RH_NRF24 nrf24;
// RH_NRF24 nrf24(8, 7); // use this to be electrically compatible with Mirf
// RH_NRF24 nrf24(8, 10);// For Leonardo, need explicit SS pin
// RH_NRF24 nrf24(8, 7); // For RFM73 on Anarduino Mini
// You can choose any of several encryption ciphers
Speck myCipher; // Instantiate a Speck block ciphering
// The RHEncryptedDriver acts as a wrapper for the actual radio driver
RHEncryptedDriver driver(nrf24, myCipher); // Instantiate the driver with those two
// The key MUST be the same as the one in the client
unsigned char encryptkey[16] = {1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16};
void setup()
{
Serial.begin(9600);
while (!Serial)
; // wait for serial port to connect. Needed for Leonardo only
if (!nrf24.init())
Serial.println("init failed");
// Defaults after init are 2.402 GHz (channel 2), 2Mbps, 0dBm
if (!nrf24.setChannel(1))
Serial.println("setChannel failed");
if (!nrf24.setRF(RH_NRF24::DataRate2Mbps, RH_NRF24::TransmitPower0dBm))
Serial.println("setRF failed");
// Now set up the encryption key in our cipher
myCipher.setKey(encryptkey, sizeof(encryptkey));
}
void loop()
{
if (driver.available())
{
// Should be a message for us now
uint8_t buf[RH_NRF24_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (driver.recv(buf, &len))
{
// RH_NRF24::printBuffer("request: ", buf, len);
Serial.print("got request: ");
Serial.println((char*)buf);
// Send a reply
uint8_t data[] = "And hello back"; // Dont make this too long
driver.send(data, sizeof(data));
driver.waitPacketSent();
Serial.println("Sent a reply");
}
else
{
Serial.println("recv failed");
}
}
}

View File

@@ -0,0 +1,63 @@
// nrf24_reliable_datagram_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, reliable messaging client
// with the RHReliableDatagram class, using the RH_NRF24 driver to control a NRF24 radio.
// It is designed to work with the other example nrf24_reliable_datagram_server
// Tested on Uno with Sparkfun WRL-00691 NRF24L01 module
// Tested on Teensy with Sparkfun WRL-00691 NRF24L01 module
// Tested on Anarduino Mini (http://www.anarduino.com/mini/) with RFM73 module
// Tested on Arduino Mega with Sparkfun WRL-00691 NRF25L01 module
#include <RHReliableDatagram.h>
#include <RH_NRF24.h>
#include <SPI.h>
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
// Singleton instance of the radio driver
RH_NRF24 driver;
// RH_NRF24 driver(8, 7); // For RFM73 on Anarduino Mini
// Class to manage message delivery and receipt, using the driver declared above
RHReliableDatagram manager(driver, CLIENT_ADDRESS);
void setup()
{
Serial.begin(9600);
if (!manager.init())
Serial.println("init failed");
// Defaults after init are 2.402 GHz (channel 2), 2Mbps, 0dBm
}
uint8_t data[] = "Hello World!";
// Dont put this on the stack:
uint8_t buf[RH_NRF24_MAX_MESSAGE_LEN];
void loop()
{
Serial.println("Sending to nrf24_reliable_datagram_server");
// Send a message to manager_server
if (manager.sendtoWait(data, sizeof(data), SERVER_ADDRESS))
{
// Now wait for a reply from the server
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAckTimeout(buf, &len, 2000, &from))
{
Serial.print("got reply from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
}
else
{
Serial.println("No reply, is nrf24_reliable_datagram_server running?");
}
}
else
Serial.println("sendtoWait failed");
delay(500);
}

View File

@@ -0,0 +1,57 @@
// nrf24_reliable_datagram_server.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, reliable messaging server
// with the RHReliableDatagram class, using the RH_NRF24 driver to control a NRF24 radio.
// It is designed to work with the other example nrf24_reliable_datagram_client
// Tested on Uno with Sparkfun WRL-00691 NRF24L01 module
// Tested on Teensy with Sparkfun WRL-00691 NRF24L01 module
// Tested on Anarduino Mini (http://www.anarduino.com/mini/) with RFM73 module
// Tested on Arduino Mega with Sparkfun WRL-00691 NRF25L01 module
#include <RHReliableDatagram.h>
#include <RH_NRF24.h>
#include <SPI.h>
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
// Singleton instance of the radio driver
RH_NRF24 driver;
// RH_NRF24 driver(8, 7); // For RFM73 on Anarduino Mini
// Class to manage message delivery and receipt, using the driver declared above
RHReliableDatagram manager(driver, SERVER_ADDRESS);
void setup()
{
Serial.begin(9600);
if (!manager.init())
Serial.println("init failed");
// Defaults after init are 2.402 GHz (channel 2), 2Mbps, 0dBm
}
uint8_t data[] = "And hello back to you";
// Dont put this on the stack:
uint8_t buf[RH_NRF24_MAX_MESSAGE_LEN];
void loop()
{
if (manager.available())
{
// Wait for a message addressed to us from the client
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
// Send a reply back to the originator client
if (!manager.sendtoWait(data, sizeof(data), from))
Serial.println("sendtoWait failed");
}
}
}

View File

@@ -0,0 +1,60 @@
// nrf24_server.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple messageing server
// with the RH_NRF24 class. RH_NRF24 class does not provide for addressing or
// reliability, so you should only use RH_NRF24 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example nrf24_client
// Tested on Uno with Sparkfun NRF25L01 module
// Tested on Anarduino Mini (http://www.anarduino.com/mini/) with RFM73 module
// Tested on Arduino Mega with Sparkfun WRL-00691 NRF25L01 module
#include <SPI.h>
#include <RH_NRF24.h>
// Singleton instance of the radio driver
RH_NRF24 nrf24;
// RH_NRF24 nrf24(8, 7); // use this to be electrically compatible with Mirf
// RH_NRF24 nrf24(8, 10);// For Leonardo, need explicit SS pin
// RH_NRF24 nrf24(8, 7); // For RFM73 on Anarduino Mini
void setup()
{
Serial.begin(9600);
while (!Serial)
; // wait for serial port to connect. Needed for Leonardo only
if (!nrf24.init())
Serial.println("init failed");
// Defaults after init are 2.402 GHz (channel 2), 2Mbps, 0dBm
if (!nrf24.setChannel(1))
Serial.println("setChannel failed");
if (!nrf24.setRF(RH_NRF24::DataRate2Mbps, RH_NRF24::TransmitPower0dBm))
Serial.println("setRF failed");
}
void loop()
{
if (nrf24.available())
{
// Should be a message for us now
uint8_t buf[RH_NRF24_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (nrf24.recv(buf, &len))
{
// NRF24::printBuffer("request: ", buf, len);
Serial.print("got request: ");
Serial.println((char*)buf);
// Send a reply
uint8_t data[] = "And hello back to you";
nrf24.send(data, sizeof(data));
nrf24.waitPacketSent();
Serial.println("Sent a reply");
}
else
{
Serial.println("recv failed");
}
}
}

View File

@@ -0,0 +1,113 @@
// nrf51_audio_rx.pde
// Sample sketch for nRF51822 and RadioHead
//
// Plays audio samples received in the radio receiver
// through a MCP4725 DAC such as on a SparkFun I2C DAC Breakout - MCP4725 (BOB-12918)
// works with matching transmitter (see nrf51_audio_tx.pde)
// Works with RedBear nRF51822 board.
// See examples/nrf51_audiotx/nrf51_audio.pdf for connection details
#include <nrf51.h>
#include <nrf51_bitfields.h>
#include <esb/nrf_esb.h>
#include <RH_NRF51.h>
#include <Wire.h>
// Number of samples per second to play at.
// Should match SAMPLE_RATE in nrf51_audio_tx
// The limiting factor is the time it takes to output a new sample through the DAC
#define SAMPLE_RATE 5000
// Number of 8 bit samples per packet
// Should equal or exceed the PACKET_SIZE in nrf51_audio_tx
#define MAX_PACKET_SIZE 255
// Singleton instance of the radio driver
RH_NRF51 driver;
void setup()
{
delay(1000);
Serial.begin(9600);
while (!Serial)
; // wait for serial port to connect.
if (!driver.init())
Serial.println("init failed");
// Defaults after init are 2.402 GHz (channel 2), 2Mbps, 0dBm
// Set up TIMER
// Use TIMER0
// Timer freq before prescaling is 16MHz (VARIANT_MCK)
// We set up a 32 bit timer that restarts every 100us and outputs a new sample
NRF_TIMER0->PRESCALER = 0 << TIMER_PRESCALER_PRESCALER_Pos;
NRF_TIMER0->MODE = TIMER_MODE_MODE_Timer << TIMER_BITMODE_BITMODE_Pos;
NRF_TIMER0->BITMODE = TIMER_BITMODE_BITMODE_32Bit << TIMER_BITMODE_BITMODE_Pos;
NRF_TIMER0->CC[0] = VARIANT_MCK / SAMPLE_RATE; // Counts per cycle
// When timer count expires, its cleared and restarts
NRF_TIMER0->SHORTS = TIMER_SHORTS_COMPARE0_CLEAR_Msk;
NRF_TIMER0->TASKS_START = 1;
// Enable an interrupt when timer completes
NRF_TIMER0->INTENSET = TIMER_INTENSET_COMPARE0_Msk;
// Enable the TIMER0 interrupt, and set the priority
// TIMER0_IRQHandler() will be called after each sample is available
NVIC_SetPriority(TIMER0_IRQn, 1);
NVIC_EnableIRQ(TIMER0_IRQn);
// Initialise comms with the I2C DAC as fast as we can
// Shame the 51822 does not suport the high speed I2C mode that the DAC does
Wire.begin(TWI_SCL, TWI_SDA, TWI_FREQUENCY_400K);
}
volatile uint32_t count = 0;
uint8_t buffer_length = 0;
uint8_t buffer[MAX_PACKET_SIZE];
uint16_t buffer_play_index = 0;
// Write this sample to analog out
void analog_out(uint8_t val)
{
// This takes about 120usecs, which
// is the limiting factor for our sample rate of 5kHz
// Writes to MCP4725 DAC over I2C using the Wire library
Wire.beginTransmission(0x60); // 7 bit addressing
Wire.write((val >> 4) & 0x0f);
Wire.write((val << 4) & 0xf0);
Wire.endTransmission();
}
// Called by timer interrupt
// Output the next available sample
void output_next_sample()
{
if (buffer_play_index < buffer_length)
{
analog_out(buffer[buffer_play_index++]);
}
}
void loop()
{
// Look for a new packet of samples
if (driver.available())
{
// expect one of these every 40ms = 25Hz
// This takes about 400us:
buffer_length = sizeof(buffer);
driver.recv(buffer, &buffer_length);
buffer_play_index = 0; // Trigger the interrupt playing of this buffer from the start
}
}
// This interrupt handler called when the timer interrupt fires
// Time to output the next sample
void TIMER0_IRQHandler(void)
{
// It is vitally important that analog output completes before
// the next interrupt becomes due!
output_next_sample();
NRF_TIMER0->EVENTS_COMPARE[0] = 0; // Clear the COMPARE[0] event and the interrupt
}

Binary file not shown.

View File

@@ -0,0 +1,143 @@
// nrf51_audio_tx.pde
// Sample sketch for nRF51822 and RadioHead
//
// Reads audio samples from an electret microphone
// via the built in ADC in the nRF51822
// Blocks of samples are sent by RadioHEad RH_NRF51 driver
// to a matching receiver (see nrf51_audio_rx.pde)
// Works with RedBear nRF51822 board.
// See examples/nrf51_audiotx/nrf51_audio.pdf for connection details
#include <nrf51.h>
#include <nrf51_bitfields.h>
#include <esb/nrf_esb.h>
#include <RH_NRF51.h>
// Number of audio samples per second
// Should match SAMPLE_RATE in nrf51_audio_rx
// Limited by the rate we can output samples in the receiver
#define SAMPLE_RATE 5000
// Number of 8 bit samples per packet
#define PACKET_SIZE 200
// Number of ADC data buffers
#define NUM_BUFFERS 2
// Minimum diff between smallest and largest reading in a given buffer
// before we will send that buffer. We dont transmit quiet signals or silence
#define USE_SQUELCH 0
#define SQUELCH_THRESHOLD 2
// These provide data transfer between the low level ADC interrupt handler and the
// higher level packet assembly and transmission
volatile uint8_t buffers[NUM_BUFFERS][PACKET_SIZE];
volatile uint16_t sample_index = 0; // Of the next sample to write
volatile uint8_t buffer_index = 0; // Of the bufferbeing filled
volatile bool buffer_ready[NUM_BUFFERS]; // Set when a buffer is full
// These hold the state of the high level transmitter code
uint8_t next_tx_buffer = 0;
// Singleton instance of the radio driver
RH_NRF51 driver;
void setup()
{
delay(1000);
Serial.begin(9600);
while (!Serial)
; // wait for serial port to connect.
if (!driver.init())
Serial.println("init failed");
// Defaults after init are 2.402 GHz (channel 2), 2Mbps, 0dBm
// Set up ADC
// Uses the builtin 1.2V bandgap reference and no prescaling
// AnalogInput2 is A0 on RedBear nrf51822 board
// Input voltage range is 0.0 to 1.2 V
NRF_ADC->CONFIG = ADC_CONFIG_RES_8bit << ADC_CONFIG_RES_Pos
| ADC_CONFIG_INPSEL_AnalogInputNoPrescaling << ADC_CONFIG_INPSEL_Pos
| ADC_CONFIG_REFSEL_VBG << ADC_CONFIG_REFSEL_Pos
| ADC_CONFIG_PSEL_AnalogInput2 << ADC_CONFIG_PSEL_Pos;
NRF_ADC->ENABLE = 1;
NRF_ADC->INTENSET = ADC_INTENSET_END_Msk; // Interrupt at completion of each sample
// Set up TIMER to trigger ADC samples
// Use TIMER0
// Timer freq before prescaling is 16MHz (VARIANT_MCK)
// We set up a 32 bit timer that restarts every 100us and trggers a new ADC sample
NRF_TIMER0->PRESCALER = 0 << TIMER_PRESCALER_PRESCALER_Pos;
NRF_TIMER0->MODE = TIMER_MODE_MODE_Timer << TIMER_BITMODE_BITMODE_Pos;
NRF_TIMER0->BITMODE = TIMER_BITMODE_BITMODE_32Bit << TIMER_BITMODE_BITMODE_Pos;
NRF_TIMER0->CC[0] = VARIANT_MCK / SAMPLE_RATE; // Counts per cycle
// When timer count expires, its cleared and restarts
NRF_TIMER0->SHORTS = TIMER_SHORTS_COMPARE0_CLEAR_Msk;
NRF_TIMER0->TASKS_START = 1;
// When the timer expires, trigger an ADC conversion
NRF_PPI->CH[0].EEP = (uint32_t)(&NRF_TIMER0->EVENTS_COMPARE[0]);
NRF_PPI->CH[0].TEP = (uint32_t)(&NRF_ADC->TASKS_START);
NRF_PPI->CHENSET = PPI_CHEN_CH0_Msk;
// Enable the ADC interrupt, and set the priority
// ADC_IRQHandler() will be called after each sample is available
NVIC_SetPriority(ADC_IRQn, 1);
NVIC_EnableIRQ(ADC_IRQn);
}
// Called when a new sample is available from the ADC.
// Add it to the current buffer.
// when the buffer is full, signal that and switch to the other buffer.
void handle_sample()
{
buffers[buffer_index][sample_index++] = NRF_ADC->RESULT;
if (sample_index >= PACKET_SIZE)
{
sample_index = 0;
buffer_ready[buffer_index] = true;
buffer_index = (buffer_index + 1) % NUM_BUFFERS;
// If the next buffer is still still full, we have an overrun
if (buffer_ready[buffer_index])
Serial.println("Overrun");
}
}
void loop() {
// Wait for the adc to fill the current buffer
if (buffer_ready[next_tx_buffer])
{
#if USE_SQUELCH
// Honour squelch settings
uint8_t min_value = 255;
uint8_t max_value = 0;
uint16_t i;
for (i = 0; i < PACKET_SIZE; i++)
{
if (buffers[next_tx_buffer][i] > max_value)
max_value = buffers[next_tx_buffer][i];
if (buffers[next_tx_buffer][i] < min_value)
min_value = buffers[next_tx_buffer][i];
}
if (max_value - min_value > SQUELCH_THRESHOLD)
#endif
{
// OK to send this one
driver.waitPacketSent(); // Make sure the previous packet has gone
driver.send((uint8_t*)buffers[next_tx_buffer], PACKET_SIZE);
}
// Now get ready to wait for the next buffer
buffer_ready[next_tx_buffer] = false;
next_tx_buffer = (next_tx_buffer + 1) % NUM_BUFFERS;
}
}
// Called as an interrupt after each new ADC sample is complete.
void ADC_IRQHandler(void)
{
NRF_ADC->EVENTS_END = 0; // Clear the end event
handle_sample();
}

View File

@@ -0,0 +1,73 @@
// nrf51_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple messageing client
// with the RH_NRF51 class. RH_NRF51 class does not provide for addressing or
// reliability, so you should only use RH_NRF51 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example nrf51_server.
// Tested on RedBearLabs nRF51822 and BLE Nano kit, built with Arduino 1.6.4.
// See http://redbearlab.com/getting-started-nrf51822/
// for how to set up your Arduino build environment
// Also tested with Sparkfun nRF52832 breakout board, witth Arduino 1.6.13 and
// Sparkfun nRF52 boards manager 0.2.3
#include <RH_NRF51.h>
// Singleton instance of the radio driver
RH_NRF51 nrf51;
void setup()
{
delay(1000); // Wait for serial port etc to be ready
Serial.begin(9600);
while (!Serial)
; // wait for serial port to connect.
if (!nrf51.init())
Serial.println("init failed");
// Defaults after init are 2.402 GHz (channel 2), 2Mbps, 0dBm
if (!nrf51.setChannel(1))
Serial.println("setChannel failed");
if (!nrf51.setRF(RH_NRF51::DataRate2Mbps, RH_NRF51::TransmitPower0dBm))
Serial.println("setRF failed");
// AES encryption can be enabled by setting the same key in the sender and receiver
// uint8_t key[] = { 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08,
// 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08};
// nrf51.setEncryptionKey(key);
// nrf51.printRegisters();
}
void loop()
{
Serial.println("Sending to nrf51_server");
// Send a message to nrf51_server
uint8_t data[] = "Hello World!";
nrf51.send(data, sizeof(data));
nrf51.waitPacketSent();
// Now wait for a reply
uint8_t buf[RH_NRF51_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (nrf51.waitAvailableTimeout(500))
{
// Should be a reply message for us now
if (nrf51.recv(buf, &len))
{
Serial.print("got reply: ");
Serial.println((char*)buf);
}
else
{
Serial.println("recv failed");
}
}
else
{
Serial.println("No reply, is nrf51_server running?");
}
delay(400);
}

View File

@@ -0,0 +1,66 @@
// nrf51_reliable_datagram_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, reliable messaging client
// with the RHReliableDatagram class, using the RH_NRF51 driver to control a NRF51 radio.
// It is designed to work with the other example nrf51_reliable_datagram_server
// Tested on RedBearLabs nRF51822 and BLE Nano kit, built with Arduino 1.6.4.
// See http://redbearlab.com/getting-started-nrf51822/
// for how to set up your Arduino build environment
// Also tested with Sparkfun nRF52832 breakout board, witth Arduino 1.6.13 and
// Sparkfun nRF52 boards manager 0.2.3
#include <RHReliableDatagram.h>
#include <RH_NRF51.h>
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
// Singleton instance of the radio driver
RH_NRF51 driver;
// Class to manage message delivery and receipt, using the driver declared above
RHReliableDatagram manager(driver, CLIENT_ADDRESS);
void setup()
{
delay(1000); // Wait for serial port etc to be ready
Serial.begin(9600);
while (!Serial)
; // wait for serial port to connect.
if (!manager.init())
Serial.println("init failed");
// Defaults after init are 2.402 GHz (channel 2), 2Mbps, 0dBm
}
uint8_t data[] = "Hello World!";
// Dont put this on the stack:
uint8_t buf[RH_NRF51_MAX_MESSAGE_LEN];
void loop()
{
Serial.println("Sending to nrf51_reliable_datagram_server");
// Send a message to manager_server
if (manager.sendtoWait(data, sizeof(data), SERVER_ADDRESS))
{
// Now wait for a reply from the server
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAckTimeout(buf, &len, 2000, &from))
{
Serial.print("got reply from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
}
else
{
Serial.println("No reply, is nrf51_reliable_datagram_server running?");
}
}
else
Serial.println("sendtoWait failed");
delay(500);
}

View File

@@ -0,0 +1,61 @@
// nrf51_reliable_datagram_server.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, reliable messaging server
// with the RHReliableDatagram class, using the RH_NRF51 driver to control a NRF51 radio.
// It is designed to work with the other example nrf51_reliable_datagram_client
// Tested on RedBearLabs nRF51822 and BLE Nano kit, built with Arduino 1.6.4.
// See http://redbearlab.com/getting-started-nrf51822/
// for how to set up your Arduino build environment
// Also tested with Sparkfun nRF52832 breakout board, witth Arduino 1.6.13 and
// Sparkfun nRF52 boards manager 0.2.3
#include <RHReliableDatagram.h>
#include <RH_NRF51.h>
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
// Singleton instance of the radio driver
RH_NRF51 driver;
// Class to manage message delivery and receipt, using the driver declared above
RHReliableDatagram manager(driver, SERVER_ADDRESS);
void setup()
{
delay(1000); // Wait for serial port etc to be ready
Serial.begin(9600);
while (!Serial)
; // wait for serial port to connect.
if (!manager.init())
Serial.println("init failed");
// Defaults after init are 2.402 GHz (channel 2), 2Mbps, 0dBm
}
uint8_t data[] = "And hello back to you";
// Dont put this on the stack:
uint8_t buf[RH_NRF51_MAX_MESSAGE_LEN];
void loop()
{
if (manager.available())
{
// Wait for a message addressed to us from the client
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
// Send a reply back to the originator client
if (!manager.sendtoWait(data, sizeof(data), from))
Serial.println("sendtoWait failed");
}
}
}

View File

@@ -0,0 +1,64 @@
// nrf51_server.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple messageing server
// with the RH_NRF51 class. RH_NRF51 class does not provide for addressing or
// reliability, so you should only use RH_NRF51 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example nrf51_client
// Tested on RedBearLabs nRF51822 and BLE Nano kit, built with Arduino 1.6.4.
// See http://redbearlab.com/getting-started-nrf51822/
// for how to set up your Arduino build environment
// Also tested with Sparkfun nRF52832 breakout board, witth Arduino 1.6.13 and
// Sparkfun nRF52 boards manager 0.2.3
#include <RH_NRF51.h>
// Singleton instance of the radio driver
RH_NRF51 nrf51;
void setup()
{
delay(1000); // Wait for serial port etc to be ready
Serial.begin(9600);
while (!Serial)
; // wait for serial port to connect. Needed for Leonardo only
if (!nrf51.init())
Serial.println("init failed");
// Defaults after init are 2.402 GHz (channel 2), 2Mbps, 0dBm
if (!nrf51.setChannel(1))
Serial.println("setChannel failed");
if (!nrf51.setRF(RH_NRF51::DataRate2Mbps, RH_NRF51::TransmitPower0dBm))
Serial.println("setRF failed");
// AES encryption can be enabled by setting the same key in the sender and receiver
// uint8_t key[] = { 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08,
// 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08};
// nrf51.setEncryptionKey(key);
}
void loop()
{
if (nrf51.available())
{
// Should be a message for us now
uint8_t buf[RH_NRF51_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (nrf51.recv(buf, &len))
{
// NRF51::printBuffer("request: ", buf, len);
Serial.print("got request: ");
Serial.println((char*)buf);
// Send a reply
uint8_t data[] = "And hello back to you";
nrf51.send(data, sizeof(data));
nrf51.waitPacketSent();
Serial.println("Sent a reply");
}
else
{
Serial.println("recv failed");
}
}
}

View File

@@ -0,0 +1,59 @@
// nrf905_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple messageing client
// with the RH_NRF905 class. RH_NRF905 class does not provide for addressing or
// reliability, so you should only use RH_NRF905 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example nrf905_server.
// Tested on Teensy3.1 with nRF905 module
// Tested on Arduino Due with nRF905 module (Caution: use the SPI headers for connecting)
#include <SPI.h>
#include <RH_NRF905.h>
// Singleton instance of the radio driver
RH_NRF905 nrf905;
void setup()
{
Serial.begin(9600);
while (!Serial)
; // wait for serial port to connect. Needed for Leonardo only
if (!nrf905.init())
Serial.println("init failed");
// Defaults after init are 433.2 MHz (channel 108), -10dBm
}
void loop()
{
Serial.println("Sending to nrf905_server");
// Send a message to nrf905_server
uint8_t data[] = "Hello World!";
nrf905.send(data, sizeof(data));
nrf905.waitPacketSent();
// Now wait for a reply
uint8_t buf[RH_NRF905_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (nrf905.waitAvailableTimeout(500))
{
// Should be a reply message for us now
if (nrf905.recv(buf, &len))
{
Serial.print("got reply: ");
Serial.println((char*)buf);
}
else
{
Serial.println("recv failed");
}
}
else
{
Serial.println("No reply, is nrf905_server running?");
}
delay(400);
}

View File

@@ -0,0 +1,60 @@
// nrf905_reliable_datagram_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, reliable messaging client
// with the RHReliableDatagram class, using the RH_NRF905 driver to control a NRF905 radio.
// It is designed to work with the other example nrf905_reliable_datagram_server
// Tested on Teensy3.1 with nRF905 module
// Tested on Arduino Due with nRF905 module (Caution: use the SPI headers for connecting)
#include <RHReliableDatagram.h>
#include <RH_NRF905.h>
#include <SPI.h>
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
// Singleton instance of the radio driver
RH_NRF905 driver;
// Class to manage message delivery and receipt, using the driver declared above
RHReliableDatagram manager(driver, CLIENT_ADDRESS);
void setup()
{
Serial.begin(9600);
if (!manager.init())
Serial.println("init failed");
// Defaults after init are 433.2 MHz (channel 108), -10dBm
}
uint8_t data[] = "Hello World!";
// Dont put this on the stack:
uint8_t buf[RH_NRF905_MAX_MESSAGE_LEN];
void loop()
{
Serial.println("Sending to nrf905_reliable_datagram_server");
// Send a message to manager_server
if (manager.sendtoWait(data, sizeof(data), SERVER_ADDRESS))
{
// Now wait for a reply from the server
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAckTimeout(buf, &len, 2000, &from))
{
Serial.print("got reply from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
}
else
{
Serial.println("No reply, is nrf905_reliable_datagram_server running?");
}
}
else
Serial.println("sendtoWait failed");
delay(500);
}

View File

@@ -0,0 +1,54 @@
// nrf905_reliable_datagram_server.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, reliable messaging server
// with the RHReliableDatagram class, using the RH_NRF905 driver to control a NRF905 radio.
// It is designed to work with the other example nrf905_reliable_datagram_client
// Tested on Teensy3.1 with nRF905 module
// Tested on Arduino Due with nRF905 module (Caution: use the SPI headers for connecting)
#include <RHReliableDatagram.h>
#include <RH_NRF905.h>
#include <SPI.h>
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
// Singleton instance of the radio driver
RH_NRF905 driver;
// Class to manage message delivery and receipt, using the driver declared above
RHReliableDatagram manager(driver, SERVER_ADDRESS);
void setup()
{
Serial.begin(9600);
if (!manager.init())
Serial.println("init failed");
// Defaults after init are 433.2 MHz (channel 108), -10dBm
}
uint8_t data[] = "And hello back to you";
// Dont put this on the stack:
uint8_t buf[RH_NRF905_MAX_MESSAGE_LEN];
void loop()
{
if (manager.available())
{
// Wait for a message addressed to us from the client
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
// Send a reply back to the originator client
if (!manager.sendtoWait(data, sizeof(data), from))
Serial.println("sendtoWait failed");
}
}
}

View File

@@ -0,0 +1,52 @@
// nrf905_server.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple messageing server
// with the RH_NRF905 class. RH_NRF905 class does not provide for addressing or
// reliability, so you should only use RH_NRF905 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example nrf905_client
// Tested on Teensy3.1 with nRF905 module
// Tested on Arduino Due with nRF905 module (Caution: use the SPI headers for connecting)
#include <SPI.h>
#include <RH_NRF905.h>
// Singleton instance of the radio driver
RH_NRF905 nrf905;
void setup()
{
Serial.begin(9600);
while (!Serial)
; // wait for serial port to connect. Needed for Leonardo only
if (!nrf905.init())
Serial.println("init failed");
// Defaults after init are 433.2 MHz (channel 108), -10dBm
}
void loop()
{
if (nrf905.available())
{
// Should be a message for us now
uint8_t buf[RH_NRF905_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (nrf905.recv(buf, &len))
{
// nrf905.printBuffer("request: ", buf, len);
Serial.print("got request: ");
Serial.println((char*)buf);
// Send a reply
uint8_t data[] = "And hello back to you";
nrf905.send(data, sizeof(data));
nrf905.waitPacketSent();
Serial.println("Sent a reply");
}
else
{
Serial.println("recv failed");
}
}
}

53
examples/raspi/Makefile Normal file
View File

@@ -0,0 +1,53 @@
# Makefile
# Sample for RH_NRF24 on Raspberry Pi
# Caution: requires bcm2835 library to be already installed
# http://www.airspayce.com/mikem/bcm2835/
CC = g++
CFLAGS = -DRASPBERRY_PI -DBCM2835_NO_DELAY_COMPATIBILITY
LIBS = -lbcm2835
RADIOHEADBASE = ../..
INCLUDE = -I$(RADIOHEADBASE)
all: RasPiRH
RasPi.o: $(RADIOHEADBASE)/RHutil/RasPi.cpp
$(CC) $(CFLAGS) -c $(RADIOHEADBASE)/RHutil/RasPi.cpp $(INCLUDE)
RasPiRH.o: RasPiRH.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RH_NRF24.o: $(RADIOHEADBASE)/RH_NRF24.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHMesh.o: $(RADIOHEADBASE)/RHMesh.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHRouter.o: $(RADIOHEADBASE)/RHRouter.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHReliableDatagram.o: $(RADIOHEADBASE)/RHReliableDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHDatagram.o: $(RADIOHEADBASE)/RHDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHHardwareSPI.o: $(RADIOHEADBASE)/RHHardwareSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHNRFSPIDriver.o: $(RADIOHEADBASE)/RHNRFSPIDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericDriver.o: $(RADIOHEADBASE)/RHGenericDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericSPI.o: $(RADIOHEADBASE)/RHGenericSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RasPiRH: RasPiRH.o RH_NRF24.o RHMesh.o RHRouter.o RHReliableDatagram.o RHDatagram.o RasPi.o RHHardwareSPI.o RHNRFSPIDriver.o RHGenericDriver.o RHGenericSPI.o
$(CC) $^ $(LIBS) -o RasPiRH
clean:
rm -rf *.o RasPiRH

138
examples/raspi/RasPiRH.cpp Normal file
View File

@@ -0,0 +1,138 @@
// RasPiRH.cpp
//
// Example program showing how to use RH_NRF24 on Raspberry Pi
// Uses the bcm2835 library to access the GPIO pins to drive the NRF24L01
// Requires bcm2835 library to be already installed
// http://www.airspayce.com/mikem/bcm2835/
// Use the Makefile in this directory:
// cd example/raspi
// make
// sudo ./RasPiRH
//
// Creates a RHReliableDatagram manager and listens and prints for reliable datagrams
// sent to it on the default Channel 2.
//
// Contributed by Mike Poublon
#include <bcm2835.h>
#include <stdio.h>
#include <signal.h>
#include <unistd.h>
#include <RHReliableDatagram.h>
#include <RH_NRF24.h>
//Function Definitions
void sig_handler(int sig);
void printbuffer(uint8_t buff[], int len);
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
// Create an instance of a driver
// Chip enable is pin 22
// Slave Select is pin 24
RH_NRF24 nrf24(RPI_V2_GPIO_P1_22, RPI_V2_GPIO_P1_24);
RHReliableDatagram manager(nrf24, SERVER_ADDRESS);
//Flag for Ctrl-C
volatile sig_atomic_t flag = 0;
//Main Function
int main (int argc, const char* argv[] )
{
signal(SIGINT, sig_handler);
if (!bcm2835_init())
{
printf( "\n\nRasPiRH Tester Startup Failed\n\n" );
return 1;
}
printf( "\nRasPiRH Tester Startup\n\n" );
/* Begin Driver Only Init Code
if (!nrf24.init())
Serial.println("init failed");
// Defaults after init are 2.402 GHz (channel 2), 2Mbps, 0dBm
if (!nrf24.setChannel(1))
Serial.println("setChannel failed");
if (!nrf24.setRF(RH_NRF24::DataRate2Mbps, RH_NRF24::TransmitPower0dBm))
Serial.println("setRF failed");
End Driver Only Init Code */
/* Begin Reliable Datagram Init Code */
if (!manager.init())
{
printf( "Init failed\n" );
}
/* End Reliable Datagram Init Code */
uint8_t buf[RH_NRF24_MAX_MESSAGE_LEN];
//Begin the main body of code
while (true)
{
uint8_t len = sizeof(buf);
uint8_t from, to, id, flags;
/* Begin Driver Only code
if (nrf24.available())
{
// Should be a message for us now
//uint8_t buf[RH_NRF24_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (nrf24.recv(buf, &len))
{
Serial.print("got request: ");
Serial.println((char*)buf);
Serial.println("");
}
else
{
Serial.println("recv failed");
}
}
End Driver Only Code*/
/* Begin Reliable Datagram Code */
if (manager.available())
{
// Wait for a message addressed to us from the client
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
}
}
/* End Reliable Datagram Code */
if (flag)
{
printf("\n---CTRL-C Caught - Exiting---\n");
break;
}
//sleep(1);
delay(25);
}
printf( "\nRasPiRH Tester Ending\n" );
bcm2835_close();
return 0;
}
void sig_handler(int sig)
{
flag=1;
}
void printbuffer(uint8_t buff[], int len)
{
for (int i = 0; i< len; i++)
{
printf(" %2X", buff[i]);
}
}

View File

@@ -0,0 +1,84 @@
# Makefile
# Example for RH_RF95 on Raspberry Pi
# Requires pigpio to be installed: http://abyz.me.uk/rpi/pigpio/
CROSSCOMPILER=$(shell if [ -z `which 'arm-linux-gnueabihf-g++'` ]; then echo "no"; else echo "yes"; fi)
ifeq ($(CROSSCOMPILER),yes)
CC = arm-linux-gnueabihf-g++
CFLAGS = -DRASPBERRY_PI -DRH_USE_MUTEX -pthread
RADIOHEADBASE = ../../../..
PIGPIOBASE = ../../../../../pigpio/
SHARED = ../shared/
INCLUDE = -I$(RADIOHEADBASE) -I$(PIGPIOBASE) -I$(SHARED)
LIBS = -lpigpio -lrt -L$(PIGPIOBASE) -lpthread -D_REENTRANT
else
CC = g++
CFLAGS = -DRASPBERRY_PI -DRH_USE_MUTEX -pthread
RADIOHEADBASE = ../../../..
PIGPIOBASE = ../../../../../pigpio/
SHARED = ../shared/
INCLUDE = -I$(RADIOHEADBASE) -I$(PIGPIOBASE) -I$(SHARED)
LIBS = -lpigpio -lrt -L$(PIGPIOBASE) -lpthread -D_REENTRANT
endif
ifeq ($(REGION),Europe)
CFLAGS += -DEUROPE
endif
ifeq ($(LORABOARD),DraginoLoraGPSHat)
CFLAGS += -DDRAGINO_GPS_HAT
endif
ifeq ($(DEBUG),1)
CFLAGS += -g3
endif
all: rf95_client1 rf95_client2
RasPi.o: $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp
$(CC) $(CFLAGS) -c $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp $(INCLUDE)
help_functions.o: $(SHARED)/help_functions.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
rf95_client1.o: rf95_client1.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
rf95_client2.o: rf95_client2.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RH_RF95.o: $(RADIOHEADBASE)/RH_RF95.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHDatagram.o: $(RADIOHEADBASE)/RHDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHHardwareSPI.o: $(RADIOHEADBASE)/RHHardwareSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHSPIDriver.o: $(RADIOHEADBASE)/RHSPIDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericDriver.o: $(RADIOHEADBASE)/RHGenericDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericSPI.o: $(RADIOHEADBASE)/RHGenericSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
gpsMT3339.o: $(SHARED)/gpsMT3339.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
rf95_client1: rf95_client1.o RH_RF95.o RHDatagram.o RasPi.o RHHardwareSPI.o RHSPIDriver.o RHGenericDriver.o RHGenericSPI.o
$(CC) $^ $(LIBS) -o rf95_client1
rf95_client2: rf95_client2.o help_functions.o RH_RF95.o RHDatagram.o RasPi.o RHHardwareSPI.o RHSPIDriver.o RHGenericDriver.o RHGenericSPI.o gpsMT3339.o
$(CC) $^ $(LIBS) -o rf95_client2
clean:
rm -rf *.o rf95_client1 rf95_client2
deploy: rf95_client1 rf95_client2
sshpass -p"$(PASSWD)" scp rf95_client1 pi@$(HOST):/home/pi
sshpass -p"$(PASSWD)" scp rf95_client2 pi@$(HOST):/home/pi

View File

@@ -0,0 +1,161 @@
// rf95_client.cpp
// -*- mode: C++ -*-
// Example app showing how to create a simple messaging client
// with the RH_RF95 class. RH_RF95 class does not provide for addressing or
// reliability, so you should only use RH_RF95 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example rf95_server.
//
// Requires Pigpio GPIO library. Install by downloading and compiling from
// http://abyz.me.uk/rpi/pigpio/, or install via command line with
// "sudo apt install pigpio". To use, run "make" at the command line in
// the folder where this source code resides. Then execute application with
// sudo ./rf95_client.
// Tested on Raspberry Pi Zero and Zero W with LoRaWan/TTN RPI Zero Shield
// by ElectronicTricks. Although this application builds and executes on
// Raspberry Pi 3, there seems to be missed messages and hangs.
// Strategically adding delays does seem to help in some cases.
//(9/20/2019) Contributed by Brody M. Based off rf22_client.pde.
// Raspberry Pi mods influenced by nrf24 example by Mike Poublon,
// and Charles-Henri Hallard (https://github.com/hallard/RadioHead)
#include <pigpio.h>
#include <stdio.h>
#include <signal.h>
#include <unistd.h>
#include <RH_RF95.h>
//Function Definitions
void sig_handler(int sig);
//Pin Definitions
#ifdef DRAGINO_GPS_HAT
// Pin definitions for lora dragino gps hat
#define RFM95_CS_PIN 25 // Slave Select on GPIO25 so P1 connector pin #22
#define RFM95_IRQ_PIN 4 // IRQ on GPIO4 so P1 connector pin #7
#define RFM95_RESET_PIN 17 // Reset on GPIO17 so P1 connector pin #11
#undef RFM95_LED // Dragino Board as no LED to drive
#else
//Pin definitions for other board
#define RFM95_CS_PIN 8
#define RFM95_IRQ_PIN 25
#define RFM95_LED 4
#endif
//Client and Server Addresses
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
//RFM95 Configuration
#ifdef EUROPE
#define RFM95_FREQUENCY 868.00
#else
#define RFM95_FREQUENCY 915.00
#endif
#define RFM95_TXPOWER 14
// Singleton instance of the radio driver
RH_RF95 rf95(RFM95_CS_PIN, RFM95_IRQ_PIN);
//Flag for Ctrl-C
int flag = 0;
//Main Function
int main (int argc, const char* argv[] )
{
if (gpioInitialise()<0)
{
printf( "\n\nRPI rf95_client startup Failed.\n" );
return 1;
}
gpioSetSignalFunc(2, sig_handler); //2 is SIGINT. Ctrl+C will cause signal.
printf( "\nRPI rf95_client startup OK.\n" );
printf( "\nRPI GPIO settings:\n" );
printf("CS-> GPIO %d\n", (uint8_t) RFM95_CS_PIN);
printf("IRQ-> GPIO %d\n", (uint8_t) RFM95_IRQ_PIN);
#ifdef RFM95_LED
gpioSetMode(RFM95_LED, PI_OUTPUT);
printf("\nINFO: LED on GPIO %d\n", (uint8_t) RFM95_LED);
gpioWrite(RFM95_LED, PI_ON);
gpioDelay(500000);
gpioWrite(RFM95_LED, PI_OFF);
#endif
if (!rf95.init())
{
printf( "\n\nRF95 driver failed to initialize.\n\n" );
return 1;
}
/* Begin Manager/Driver settings code */
printf("\nRFM 95 Settings:\n");
printf("Frequency= %d MHz\n", (uint16_t) RFM95_FREQUENCY);
printf("Power= %d\n", (uint8_t) RFM95_TXPOWER);
printf("Client(This) Address= %d\n", CLIENT_ADDRESS);
printf("Server Address= %d\n", SERVER_ADDRESS);
rf95.setTxPower(RFM95_TXPOWER, false);
rf95.setFrequency(RFM95_FREQUENCY);
rf95.setThisAddress(CLIENT_ADDRESS);
rf95.setHeaderFrom(CLIENT_ADDRESS);
rf95.setHeaderTo(SERVER_ADDRESS);
rf95.setModemConfig(RH_RF95::Bw125Cr48Sf4096);
/* End Manager/Driver settings code */
/* Begin Datagram Client Code */
while(!flag)
{
Serial.println("Sending to rf95_server");
// Send a message to rf95_server
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_ON);
#endif
uint8_t data[] = "Hello World!";
rf95.send(data, sizeof(data));
rf95.waitPacketSent();
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_OFF);
#endif
// Now wait for a reply
uint8_t buf[RH_RF95_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (rf95.waitAvailableTimeout(3000))
{
// Should be a reply message for us now
if (rf95.recv(buf, &len))
{
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_ON);
#endif
Serial.print("got reply: ");
Serial.println((char*)buf);
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_OFF);
#endif
}
else
{
Serial.println("recv failed");
}
}
else
{
Serial.println("No reply, is rf95_server running?");
}
gpioDelay(400000);
}
printf( "\nrf95_client Tester Ending\n" );
gpioTerminate();
return 0;
}
void sig_handler(int sig)
{
flag=1;
}

View File

@@ -0,0 +1,250 @@
// rf95_client.cpp
// -*- mode: C++ -*-
// Example app showing how to create a simple messaging client
// with the RH_RF95 class. RH_RF95 class does not provide for addressing or
// reliability, so you should only use RH_RF95 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example rf95_server.
//
// Requires Pigpio GPIO library. Install by downloading and compiling from
// http://abyz.me.uk/rpi/pigpio/, or install via command line with
// "sudo apt install pigpio". To use, run "make" at the command line in
// the folder where this source code resides. Then execute application with
// sudo ./rf95_client.
// Tested on Raspberry Pi Zero and Zero W with LoRaWan/TTN RPI Zero Shield
// by ElectronicTricks. Although this application builds and executes on
// Raspberry Pi 3, there seems to be missed messages and hangs.
// Strategically adding delays does seem to help in some cases.
//(9/20/2019) Contributed by Brody M. Based off rf22_client.pde.
// Raspberry Pi mods influenced by nrf24 example by Mike Poublon,
// and Charles-Henri Hallard (https://github.com/hallard/RadioHead)
#include <pigpio.h>
#include <stdio.h>
#include <signal.h>
#include <unistd.h>
#include <RH_RF95.h>
#include <help_functions.h>
//Function Definitions
void sig_handler(int sig);
#ifdef DRAGINO_GPS_HAT
pthread_mutex_t gps_data_mutex;
#include <gpsMT3339.h>
// Pin definitions for dragino gps hat
#define RFM95_CS_PIN 25 // Slave Select on GPIO25 so P1 connector pin #22
#define RFM95_IRQ_PIN 4 // IRQ on GPIO4 so P1 connector pin #7
#define RFM95_RESET_PIN 17 // Reset on GPIO17 so P1 connector pin #11
#undef RFM95_LED // Dragino Board as no LED to drive
#else
//Pin definitions for other board
#define RFM95_CS_PIN 8
#define RFM95_IRQ_PIN 25
#define RFM95_LED 4
#endif
//Client and Server Addresses
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
//RFM95 Configuration
#ifdef EUROPE
#define RFM95_FREQUENCY 868.00
#else
#define RFM95_FREQUENCY 915.00
#endif
#define RFM95_TXPOWER 14
// Singleton instance of the radio driver
RH_RF95 rf95(RFM95_CS_PIN, RFM95_IRQ_PIN);
#ifdef DRAGINO_GPS_HAT
gps_MT3339 gps(GPS_DEVICE, &gps_data_mutex);
#endif
//Flag for Ctrl-C
int flag = 0;
// function to handle Lora device
void* lora_main(void* ptr)
{
#ifndef DRAGINO_GPS_HAT
char temp[10];
uint8_t data[] = "Hello World(xxxxx)!";
#else
uint8_t data[50];
#endif
uint16_t sequenceCounter = 0;
printf("\nLORA Handler started\n");
print_scheduler();
print_scope();
while(!flag)
{
// printf("Sending to rf95_server");
// Send a message to rf95_server
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_ON);
#endif
#ifndef DRAGINO_GPS_HAT
snprintf(temp,6,"%05d",sequenceCounter);
strncpy((char*)data+12,temp,5);
#else
pthread_mutex_lock(&gps_data_mutex);
snprintf((char*)data,45,"(%05d):%10s,%10s,%11s",sequenceCounter,gps.getTimestamp(),gps.getLatitude(),gps.getLongitude());
pthread_mutex_unlock(&gps_data_mutex);
#endif
printf("Message=\"");
printf("%s",(char*)data);
printf("\"\n");
rf95.send(data, sizeof(data));
sequenceCounter++;
rf95.waitPacketSent();
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_OFF);
#endif
// Now wait for a reply
uint8_t buf[RH_RF95_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (rf95.waitAvailableTimeout(5000))
{
// Should be a reply message for us now
if (rf95.recv(buf, &len))
{
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_ON);
#endif
printf("got reply: ");
printf("\"%s\"\n",(char*)buf);
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_OFF);
#endif
}
else
{
printf("recv failed");
}
}
else
{
printf("No reply, is rf95_server running?\n");
}
#ifdef DRAGINO_GPS_HAT
pthread_yield();
#endif
}
}
//Main Function
int main (int argc, const char* argv[] )
{
// startup
if (gpioInitialise()<0)
{
printf( "\n\nRPI rf95_client startup Failed.\n" );
gpioTerminate();
return 1;
}
gpioSetSignalFunc(2, sig_handler); //2 is SIGINT. Ctrl+C will cause signal.
printf( "\nRPI rf95_client startup OK.\n" );
printf( "\nRPI GPIO settings:\n" );
printf("CS-> GPIO %d\n", (uint8_t) RFM95_CS_PIN);
printf("IRQ-> GPIO %d\n", (uint8_t) RFM95_IRQ_PIN);
#ifdef RFM95_LED
gpioSetMode(RFM95_LED, PI_OUTPUT);
printf("\nINFO: LED on GPIO %d\n", (uint8_t) RFM95_LED);
gpioWrite(RFM95_LED, PI_ON);
gpioDelay(500000);
gpioWrite(RFM95_LED, PI_OFF);
#endif
#ifdef RFM95_RESET_PIN
printf( "RST-> GPIO %d\n", (uint8_t) RFM95_RESET_PIN );
// Pulse a reset on module
gpioSetMode(RFM95_RESET_PIN, PI_OUTPUT);
digitalWrite(RFM95_RESET_PIN, LOW );
gpioDelay(150);
digitalWrite(RFM95_RESET_PIN, HIGH );
gpioDelay(100);
#endif
if (!rf95.init())
{
printf( "\n\nRF95 driver failed to initialize.\n\n" );
gpioTerminate();
return 1;
}
printf("\nRFM 95 Device Version:0x%x\n",rf95.getDeviceVersion());
/* Begin Manager/Driver settings code */
printf("\nRFM 95 Settings:\n");
printf("Frequency= %d MHz\n", (uint16_t) RFM95_FREQUENCY);
printf("Power= %d\n", (uint8_t) RFM95_TXPOWER);
printf("Client(This) Address= %d\n", CLIENT_ADDRESS);
printf("Server Address= %d\n", SERVER_ADDRESS);
rf95.setTxPower(RFM95_TXPOWER, false);
rf95.setFrequency(RFM95_FREQUENCY);
rf95.setThisAddress(CLIENT_ADDRESS);
rf95.setHeaderFrom(CLIENT_ADDRESS);
rf95.setHeaderTo(SERVER_ADDRESS);
rf95.setModemConfig(RH_RF95::Bw125Cr48Sf4096);
/* End Manager/Driver settings code */
/* Begin Datagram Client Code */
#ifdef DRAGINO_GPS_HAT
pthread_t read_gps_thread, lora_thread;
int iret;
pthread_mutex_init(&gps_data_mutex,NULL);
iret = pthread_create( &read_gps_thread, NULL, ((void* (*)(void*))&gps_MT3339::read_gps), &gps);
if (iret != 0)
printf("\nCould not start thread to read gps data\n");
iret = pthread_create( &lora_thread, NULL, lora_main, NULL);
if (iret != 0)
printf("\nCould not start thread to handle lora\n");
print_scheduler();
#endif
// main loop
while(!flag)
{
#ifndef DRAGINO_GPS_HAT
lora_main(NULL);
#else
sleep(1);
#endif
}
printf( "\nrf95_client Tester Ending\n" );
#ifdef DRAGINO_GPS_HAT
pthread_join(lora_thread,NULL);
pthread_join(read_gps_thread,NULL);
#endif
gpioTerminate();
return 0;
}
// signal handler terminating the program on CTRL-c
void sig_handler(int sig)
{
flag=1;
#ifdef DRAGINO_GPS_HAT
gps.stop();
#endif
}

View File

@@ -0,0 +1,52 @@
# Makefile
# Example for RH_RF95 on Raspberry Pi
# Requires pigpio to be installed: http://abyz.me.uk/rpi/pigpio/
CC = g++
CFLAGS = -DRASPBERRY_PI -pthread
LIBS = -lpigpio -lrt
RADIOHEADBASE = ../../../..
INCLUDE = -I$(RADIOHEADBASE)
all: rf95_mesh_client
RasPi.o: $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp
$(CC) $(CFLAGS) -c $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp $(INCLUDE)
rf95_mesh_client.o: rf95_mesh_client.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RH_RF95.o: $(RADIOHEADBASE)/RH_RF95.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHMesh.o: $(RADIOHEADBASE)/RHMesh.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHRouter.o: $(RADIOHEADBASE)/RHRouter.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHReliableDatagram.o: $(RADIOHEADBASE)/RHReliableDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHDatagram.o: $(RADIOHEADBASE)/RHDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHHardwareSPI.o: $(RADIOHEADBASE)/RHHardwareSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHSPIDriver.o: $(RADIOHEADBASE)/RHSPIDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericDriver.o: $(RADIOHEADBASE)/RHGenericDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericSPI.o: $(RADIOHEADBASE)/RHGenericSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
rf95_mesh_client: rf95_mesh_client.o RH_RF95.o RHMesh.o RHRouter.o RHReliableDatagram.o RHDatagram.o RasPi.o RHHardwareSPI.o RHSPIDriver.o RHGenericDriver.o RHGenericSPI.o
$(CC) $^ $(LIBS) -o rf95_mesh_client
clean:
rm -rf *.o rf95_mesh_client

View File

@@ -0,0 +1,151 @@
// rf95_mesh_client.cpp
// -*- mode: C++ -*-
// Example application showing how to create a simple addressed, routed reliable messaging client
// with the RHMesh class.
// It is designed to work with the other examples rf95_mesh_server*
// Hint: you can simulate other network topologies by setting the
// RH_TEST_NETWORK define in RHRouter.h
// Mesh has much greater memory requirements, and you may need to limit the
// max message length to prevent wierd crashes
//
// Requires Pigpio GPIO library. Install by downloading and compiling from
// http://abyz.me.uk/rpi/pigpio/, or install via command line with
// "sudo apt install pigpio". To use, run "make" at the command line in
// the folder where this source code resides. Then execute application with
// sudo ./rf95_mesh_client.
// Tested on Raspberry Pi Zero and Zero W with LoRaWan/TTN RPI Zero Shield
// by ElectronicTricks. Although this application builds and executes on
// Raspberry Pi 3, there seems to be missed messages and hangs.
// Strategically adding delays does seem to help in some cases.
//(9/20/2019) Contributed by Brody M. Based off rf22_mesh_client.pde.
// Raspberry Pi mods influenced by nrf24 example by Mike Poublon,
// and Charles-Henri Hallard (https://github.com/hallard/RadioHead)
#include <pigpio.h>
#include <stdio.h>
#include <signal.h>
#include <unistd.h>
#include <RHMesh.h>
#include <RH_RF95.h>
#define RH_MESH_MAX_MESSAGE_LEN 50
//Function Definitions
void sig_handler(int sig);
//Pin Definitions
#define RFM95_CS_PIN 8
#define RFM95_IRQ_PIN 25
#define RFM95_LED 4
// In this small artifical network of 4 nodes,
#define CLIENT_ADDRESS 1
#define SERVER1_ADDRESS 2
#define SERVER2_ADDRESS 3
#define SERVER3_ADDRESS 4
//RFM95 Configuration
#define RFM95_FREQUENCY 915.00
#define RFM95_TXPOWER 14
// Singleton instance of the radio driver
RH_RF95 rf95(RFM95_CS_PIN, RFM95_IRQ_PIN);
// Class to manage message delivery and receipt, using the driver declared above
RHMesh manager(rf95, CLIENT_ADDRESS);
//Flag for Ctrl-C
int flag = 0;
//Main Function
int main (int argc, const char* argv[] )
{
if (gpioInitialise()<0)
{
printf( "\n\nRPI rf95_mesh_client startup Failed.\n" );
return 1;
}
gpioSetSignalFunc(2, sig_handler); //2 is SIGINT. Ctrl+C will cause signal.
printf( "\nRPI rf95_mesh_client startup OK.\n" );
#ifdef RFM95_LED
gpioSetMode(RFM95_LED, PI_OUTPUT);
printf("\nINFO: LED on GPIO %d\n", (uint8_t) RFM95_LED);
gpioWrite(RFM95_LED, PI_ON);
gpioDelay(500000);
gpioWrite(RFM95_LED, PI_OFF);
#endif
if (!manager.init())
{
printf( "\n\nMesh Manager Failed to initialize.\n\n" );
return 1;
}
/* Begin Manager/Driver settings code */
printf("\nRFM 95 Settings:\n");
printf("Frequency= %d MHz\n", (uint16_t) RFM95_FREQUENCY);
printf("Power= %d\n", (uint8_t) RFM95_TXPOWER);
printf("Client(This) Address= %d\n", CLIENT_ADDRESS);
printf("Server Address 1= %d\n", SERVER1_ADDRESS);
printf("Server Address 2= %d\n", SERVER2_ADDRESS);
printf("Server Address 3= %d\n", SERVER3_ADDRESS);
printf("Route: Client->Server 3 is automatic in MESH.\n");
rf95.setTxPower(RFM95_TXPOWER, false);
rf95.setFrequency(RFM95_FREQUENCY);
/* End Manager/Driver settings code */
uint8_t data[] = "Hello World!";
// Dont put this on the stack:
uint8_t buf[RH_MESH_MAX_MESSAGE_LEN];
while(!flag)
{
Serial.println("Sending to manager_mesh_server3");
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_ON);
#endif
// Send a message to a rf95_mesh_server
// A route to the destination will be automatically discovered.
if (manager.sendtoWait(data, sizeof(data), SERVER3_ADDRESS) == RH_ROUTER_ERROR_NONE)
{
// It has been reliably delivered to the next node.
// Now wait for a reply from the ultimate server
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAckTimeout(buf, &len, 3000, &from))
{
Serial.print("got reply from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
}
else
{
Serial.println("No reply, is rf95_mesh_server1, rf95_mesh_server2 and rf95_mesh_server3 running?");
}
}
else
Serial.println("sendtoWait failed. Are the intermediate mesh servers running?");
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_OFF);
#endif
gpioDelay(400000);
}
printf( "\nrf95_mesh_client Tester Ending\n" );
gpioTerminate();
return 0;
}
void sig_handler(int sig)
{
flag=1;
}

View File

@@ -0,0 +1,52 @@
# Makefile
# Example for RH_RF95 on Raspberry Pi
# Requires pigpio to be installed: http://abyz.me.uk/rpi/pigpio/
CC = g++
CFLAGS = -DRASPBERRY_PI -pthread
LIBS = -lpigpio -lrt
RADIOHEADBASE = ../../../..
INCLUDE = -I$(RADIOHEADBASE)
all: rf95_mesh_server1
RasPi.o: $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp
$(CC) $(CFLAGS) -c $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp $(INCLUDE)
rf95_mesh_server1.o: rf95_mesh_server1.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RH_RF95.o: $(RADIOHEADBASE)/RH_RF95.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHMesh.o: $(RADIOHEADBASE)/RHMesh.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHRouter.o: $(RADIOHEADBASE)/RHRouter.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHReliableDatagram.o: $(RADIOHEADBASE)/RHReliableDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHDatagram.o: $(RADIOHEADBASE)/RHDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHHardwareSPI.o: $(RADIOHEADBASE)/RHHardwareSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHSPIDriver.o: $(RADIOHEADBASE)/RHSPIDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericDriver.o: $(RADIOHEADBASE)/RHGenericDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericSPI.o: $(RADIOHEADBASE)/RHGenericSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
rf95_mesh_server1: rf95_mesh_server1.o RH_RF95.o RHMesh.o RHRouter.o RHReliableDatagram.o RHDatagram.o RasPi.o RHHardwareSPI.o RHSPIDriver.o RHGenericDriver.o RHGenericSPI.o
$(CC) $^ $(LIBS) -o rf95_mesh_server1
clean:
rm -rf *.o rf95_mesh_server1

View File

@@ -0,0 +1,138 @@
// rf95_mesh_server1.cpp
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, routed reliable messaging server
// with the RHMesh class.
// It is designed to work with the other examples rf95_mesh_*
// Hint: you can simulate other network topologies by setting the
// RH_TEST_NETWORK define in RHRouter.h
// Mesh has much greater memory requirements, and you may need to limit the
// max message length to prevent wierd crashes
//
// Requires Pigpio GPIO library. Install by downloading and compiling from
// http://abyz.me.uk/rpi/pigpio/, or install via command line with
// "sudo apt install pigpio". To use, run "make" at the command line in
// the folder where this source code resides. Then execute application with
// sudo ./rf95_mesh_server1.
// Tested on Raspberry Pi Zero and Zero W with LoRaWan/TTN RPI Zero Shield
// by ElectronicTricks. Although this application builds and executes on
// Raspberry Pi 3, there seems to be missed messages and hangs.
// Strategically adding delays does seem to help in some cases.
//(9/20/2019) Contributed by Brody M. Based off rf22_mesh_server1.pde.
// Raspberry Pi mods influenced by nrf24 example by Mike Poublon,
// and Charles-Henri Hallard (https://github.com/hallard/RadioHead)
#include <pigpio.h>
#include <stdio.h>
#include <signal.h>
#include <unistd.h>
#include <RHMesh.h>
#include <RH_RF95.h>
#define RH_MESH_MAX_MESSAGE_LEN 50
//Function Definitions
void sig_handler(int sig);
//Pin Definitions
#define RFM95_CS_PIN 8
#define RFM95_IRQ_PIN 25
#define RFM95_LED 4
// In this small artifical network of 4 nodes,
#define CLIENT_ADDRESS 1
#define SERVER1_ADDRESS 2
#define SERVER2_ADDRESS 3
#define SERVER3_ADDRESS 4
//RFM95 Configuration
#define RFM95_FREQUENCY 915.00
#define RFM95_TXPOWER 14
// Singleton instance of the radio driver
RH_RF95 rf95(RFM95_CS_PIN, RFM95_IRQ_PIN);
// Class to manage message delivery and receipt, using the driver declared above
RHMesh manager(rf95, SERVER1_ADDRESS);
//Flag for Ctrl-C
int flag = 0;
//Main Function
int main (int argc, const char* argv[] )
{
if (gpioInitialise()<0)
{
printf( "\n\nRPI rf95_mesh_server1 startup Failed.\n" );
return 1;
}
gpioSetSignalFunc(2, sig_handler); //2 is SIGINT. Ctrl+C will cause signal.
printf( "\nRPI rf95_mesh_server1 startup OK.\n" );
#ifdef RFM95_LED
gpioSetMode(RFM95_LED, PI_OUTPUT);
printf("\nINFO: LED on GPIO %d\n", (uint8_t) RFM95_LED);
gpioWrite(RFM95_LED, PI_ON);
gpioDelay(500000);
gpioWrite(RFM95_LED, PI_OFF);
#endif
if (!manager.init())
{
printf( "\n\nMesh Manager Failed to initialize.\n\n" );
return 1;
}
/* Begin Manager/Driver settings code */
printf("\nRFM 95 Settings:\n");
printf("Frequency= %d MHz\n", (uint16_t) RFM95_FREQUENCY);
printf("Power= %d\n", (uint8_t) RFM95_TXPOWER);
printf("Client Address= %d\n", CLIENT_ADDRESS);
printf("Server(This) Address 1= %d\n", SERVER1_ADDRESS);
printf("Server Address 2= %d\n", SERVER2_ADDRESS);
printf("Server Address 3= %d\n", SERVER3_ADDRESS);
printf("Route: Client->Server 3 is automatic in MESH.\n");
rf95.setTxPower(RFM95_TXPOWER, false);
rf95.setFrequency(RFM95_FREQUENCY);
/* End Manager/Driver settings code */
uint8_t data[] = "And hello back to you from server1";
// Dont put this on the stack:
uint8_t buf[RH_MESH_MAX_MESSAGE_LEN];
while(!flag)
{
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_ON);
#endif
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
// Send a reply back to the originator client
if (manager.sendtoWait(data, sizeof(data), from) != RH_ROUTER_ERROR_NONE)
Serial.println("sendtoWait failed");
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_OFF);
#endif
}
}
printf( "\nrf95_mesh_server1 Tester Ending\n" );
gpioTerminate();
return 0;
}
void sig_handler(int sig)
{
flag=1;
}

View File

@@ -0,0 +1,52 @@
# Makefile
# Example for RH_RF95 on Raspberry Pi
# Requires pigpio to be installed: http://abyz.me.uk/rpi/pigpio/
CC = g++
CFLAGS = -DRASPBERRY_PI -pthread
LIBS = -lpigpio -lrt
RADIOHEADBASE = ../../../..
INCLUDE = -I$(RADIOHEADBASE)
all: rf95_mesh_server2
RasPi.o: $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp
$(CC) $(CFLAGS) -c $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp $(INCLUDE)
rf95_mesh_server2.o: rf95_mesh_server2.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RH_RF95.o: $(RADIOHEADBASE)/RH_RF95.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHMesh.o: $(RADIOHEADBASE)/RHMesh.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHRouter.o: $(RADIOHEADBASE)/RHRouter.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHReliableDatagram.o: $(RADIOHEADBASE)/RHReliableDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHDatagram.o: $(RADIOHEADBASE)/RHDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHHardwareSPI.o: $(RADIOHEADBASE)/RHHardwareSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHSPIDriver.o: $(RADIOHEADBASE)/RHSPIDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericDriver.o: $(RADIOHEADBASE)/RHGenericDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericSPI.o: $(RADIOHEADBASE)/RHGenericSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
rf95_mesh_server2: rf95_mesh_server2.o RH_RF95.o RHMesh.o RHRouter.o RHReliableDatagram.o RHDatagram.o RasPi.o RHHardwareSPI.o RHSPIDriver.o RHGenericDriver.o RHGenericSPI.o
$(CC) $^ $(LIBS) -o rf95_mesh_server2
clean:
rm -rf *.o rf95_mesh_server2

View File

@@ -0,0 +1,138 @@
// rf95_mesh_server2.cpp
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, routed reliable messaging server
// with the RHMesh class.
// It is designed to work with the other examples rf95_mesh_*
// Hint: you can simulate other network topologies by setting the
// RH_TEST_NETWORK define in RHRouter.h
// Mesh has much greater memory requirements, and you may need to limit the
// max message length to prevent wierd crashes
//
// Requires Pigpio GPIO library. Install by downloading and compiling from
// http://abyz.me.uk/rpi/pigpio/, or install via command line with
// "sudo apt install pigpio". To use, run "make" at the command line in
// the folder where this source code resides. Then execute application with
// sudo ./rf95_mesh_server2.
// Tested on Raspberry Pi Zero and Zero W with LoRaWan/TTN RPI Zero Shield
// by ElectronicTricks. Although this application builds and executes on
// Raspberry Pi 3, there seems to be missed messages and hangs.
// Strategically adding delays does seem to help in some cases.
//(9/20/2019) Contributed by Brody M. Based off rf22_mesh_server2.pde.
// Raspberry Pi mods influenced by nrf24 example by Mike Poublon,
// and Charles-Henri Hallard (https://github.com/hallard/RadioHead)
#include <pigpio.h>
#include <stdio.h>
#include <signal.h>
#include <unistd.h>
#include <RHMesh.h>
#include <RH_RF95.h>
#define RH_MESH_MAX_MESSAGE_LEN 50
//Function Definitions
void sig_handler(int sig);
//Pin Definitions
#define RFM95_CS_PIN 8
#define RFM95_IRQ_PIN 25
#define RFM95_LED 4
// In this small artifical network of 4 nodes,
#define CLIENT_ADDRESS 1
#define SERVER1_ADDRESS 2
#define SERVER2_ADDRESS 3
#define SERVER3_ADDRESS 4
//RFM95 Configuration
#define RFM95_FREQUENCY 915.00
#define RFM95_TXPOWER 14
// Singleton instance of the radio driver
RH_RF95 rf95(RFM95_CS_PIN, RFM95_IRQ_PIN);
// Class to manage message delivery and receipt, using the driver declared above
RHMesh manager(rf95, SERVER2_ADDRESS);
//Flag for Ctrl-C
int flag = 0;
//Main Function
int main (int argc, const char* argv[] )
{
if (gpioInitialise()<0)
{
printf( "\n\nRPI rf95_mesh_server2 startup Failed.\n" );
return 1;
}
gpioSetSignalFunc(2, sig_handler); //2 is SIGINT. Ctrl+C will cause signal.
printf( "\nRPI rf95_mesh_server2 startup OK.\n" );
#ifdef RFM95_LED
gpioSetMode(RFM95_LED, PI_OUTPUT);
printf("\nINFO: LED on GPIO %d\n", (uint8_t) RFM95_LED);
gpioWrite(RFM95_LED, PI_ON);
gpioDelay(500000);
gpioWrite(RFM95_LED, PI_OFF);
#endif
if (!manager.init())
{
printf( "\n\nMesh Manager Failed to initialize.\n\n" );
return 1;
}
/* Begin Manager/Driver settings code */
printf("\nRFM 95 Settings:\n");
printf("Frequency= %d MHz\n", (uint16_t) RFM95_FREQUENCY);
printf("Power= %d\n", (uint8_t) RFM95_TXPOWER);
printf("Client Address= %d\n", CLIENT_ADDRESS);
printf("Server Address 1= %d\n", SERVER1_ADDRESS);
printf("Server(This) Address 2= %d\n", SERVER2_ADDRESS);
printf("Server Address 3= %d\n", SERVER3_ADDRESS);
printf("Route: Client->Server 3 is automatic in MESH.\n");
rf95.setTxPower(RFM95_TXPOWER, false);
rf95.setFrequency(RFM95_FREQUENCY);
/* End Manager/Driver settings code */
uint8_t data[] = "And hello back to you from server2";
// Dont put this on the stack:
uint8_t buf[RH_MESH_MAX_MESSAGE_LEN];
while(!flag)
{
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_ON);
#endif
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
// Send a reply back to the originator client
if (manager.sendtoWait(data, sizeof(data), from) != RH_ROUTER_ERROR_NONE)
Serial.println("sendtoWait failed");
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_OFF);
#endif
}
}
printf( "\nrf95_mesh_server2 Tester Ending\n" );
gpioTerminate();
return 0;
}
void sig_handler(int sig)
{
flag=1;
}

View File

@@ -0,0 +1,52 @@
# Makefile
# Example for RH_RF95 on Raspberry Pi
# Requires pigpio to be installed: http://abyz.me.uk/rpi/pigpio/
CC = g++
CFLAGS = -DRASPBERRY_PI -pthread
LIBS = -lpigpio -lrt
RADIOHEADBASE = ../../../..
INCLUDE = -I$(RADIOHEADBASE)
all: rf95_mesh_server3
RasPi.o: $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp
$(CC) $(CFLAGS) -c $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp $(INCLUDE)
rf95_mesh_server3.o: rf95_mesh_server3.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RH_RF95.o: $(RADIOHEADBASE)/RH_RF95.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHMesh.o: $(RADIOHEADBASE)/RHMesh.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHRouter.o: $(RADIOHEADBASE)/RHRouter.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHReliableDatagram.o: $(RADIOHEADBASE)/RHReliableDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHDatagram.o: $(RADIOHEADBASE)/RHDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHHardwareSPI.o: $(RADIOHEADBASE)/RHHardwareSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHSPIDriver.o: $(RADIOHEADBASE)/RHSPIDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericDriver.o: $(RADIOHEADBASE)/RHGenericDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericSPI.o: $(RADIOHEADBASE)/RHGenericSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
rf95_mesh_server3: rf95_mesh_server3.o RH_RF95.o RHMesh.o RHRouter.o RHReliableDatagram.o RHDatagram.o RasPi.o RHHardwareSPI.o RHSPIDriver.o RHGenericDriver.o RHGenericSPI.o
$(CC) $^ $(LIBS) -o rf95_mesh_server3
clean:
rm -rf *.o rf95_mesh_server3

View File

@@ -0,0 +1,138 @@
// rf95_mesh_server3.cpp
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, routed reliable messaging server
// with the RHMesh class.
// It is designed to work with the other examples rf95_mesh_*
// Hint: you can simulate other network topologies by setting the
// RH_TEST_NETWORK define in RHRouter.h
// Mesh has much greater memory requirements, and you may need to limit the
// max message length to prevent wierd crashes
//
// Requires Pigpio GPIO library. Install by downloading and compiling from
// http://abyz.me.uk/rpi/pigpio/, or install via command line with
// "sudo apt install pigpio". To use, run "make" at the command line in
// the folder where this source code resides. Then execute application with
// sudo ./rf95_mesh_server3.
// Tested on Raspberry Pi Zero and Zero W with LoRaWan/TTN RPI Zero Shield
// by ElectronicTricks. Although this application builds and executes on
// Raspberry Pi 3, there seems to be missed messages and hangs.
// Strategically adding delays does seem to help in some cases.
//(9/20/2019) Contributed by Brody M. Based off rf22_mesh_server3.pde.
// Raspberry Pi mods influenced by nrf24 example by Mike Poublon,
// and Charles-Henri Hallard (https://github.com/hallard/RadioHead)
#include <pigpio.h>
#include <stdio.h>
#include <signal.h>
#include <unistd.h>
#include <RHMesh.h>
#include <RH_RF95.h>
#define RH_MESH_MAX_MESSAGE_LEN 50
//Function Definitions
void sig_handler(int sig);
//Pin Definitions
#define RFM95_CS_PIN 8
#define RFM95_IRQ_PIN 25
#define RFM95_LED 4
// In this small artifical network of 4 nodes,
#define CLIENT_ADDRESS 1
#define SERVER1_ADDRESS 2
#define SERVER2_ADDRESS 3
#define SERVER3_ADDRESS 4
//RFM95 Configuration
#define RFM95_FREQUENCY 915.00
#define RFM95_TXPOWER 14
// Singleton instance of the radio driver
RH_RF95 rf95(RFM95_CS_PIN, RFM95_IRQ_PIN);
// Class to manage message delivery and receipt, using the driver declared above
RHMesh manager(rf95, SERVER3_ADDRESS);
//Flag for Ctrl-C
int flag = 0;
//Main Function
int main (int argc, const char* argv[] )
{
if (gpioInitialise()<0)
{
printf( "\n\nRPI rf95_mesh_server3 startup Failed.\n" );
return 1;
}
gpioSetSignalFunc(2, sig_handler); //2 is SIGINT. Ctrl+C will cause signal.
printf( "\nRPI rf95_mesh_server2 startup OK.\n" );
#ifdef RFM95_LED
gpioSetMode(RFM95_LED, PI_OUTPUT);
printf("\nINFO: LED on GPIO %d\n", (uint8_t) RFM95_LED);
gpioWrite(RFM95_LED, PI_ON);
gpioDelay(500000);
gpioWrite(RFM95_LED, PI_OFF);
#endif
if (!manager.init())
{
printf( "\n\nMesh Manager Failed to initialize.\n\n" );
return 1;
}
/* Begin Manager/Driver settings code */
printf("\nRFM 95 Settings:\n");
printf("Frequency= %d MHz\n", (uint16_t) RFM95_FREQUENCY);
printf("Power= %d\n", (uint8_t) RFM95_TXPOWER);
printf("Client Address= %d\n", CLIENT_ADDRESS);
printf("Server Address 1= %d\n", SERVER1_ADDRESS);
printf("Server Address 2= %d\n", SERVER2_ADDRESS);
printf("Server(This) Address 3= %d\n", SERVER3_ADDRESS);
printf("Route: Client->Server 3 is automatic in MESH.\n");
rf95.setTxPower(RFM95_TXPOWER, false);
rf95.setFrequency(RFM95_FREQUENCY);
/* End Manager/Driver settings code */
uint8_t data[] = "And hello back to you from server3";
// Dont put this on the stack:
uint8_t buf[RH_MESH_MAX_MESSAGE_LEN];
while(!flag)
{
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_ON);
#endif
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
// Send a reply back to the originator client
if (manager.sendtoWait(data, sizeof(data), from) != RH_ROUTER_ERROR_NONE)
Serial.println("sendtoWait failed");
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_OFF);
#endif
}
}
printf( "\nrf95_mesh_server3 Tester Ending\n" );
gpioTerminate();
return 0;
}
void sig_handler(int sig)
{
flag=1;
}

View File

@@ -0,0 +1,46 @@
# Makefile
# Example for RH_RF95 on Raspberry Pi
# Requires pigpio to be installed: http://abyz.me.uk/rpi/pigpio/
CC = g++
CFLAGS = -DRASPBERRY_PI -pthread
LIBS = -lpigpio -lrt
RADIOHEADBASE = ../../../..
INCLUDE = -I$(RADIOHEADBASE)
all: rf95_reliable_datagram_client
RasPi.o: $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp
$(CC) $(CFLAGS) -c $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp $(INCLUDE)
rf95_reliable_datagram_client.o: rf95_reliable_datagram_client.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RH_RF95.o: $(RADIOHEADBASE)/RH_RF95.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHReliableDatagram.o: $(RADIOHEADBASE)/RHReliableDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHDatagram.o: $(RADIOHEADBASE)/RHDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHHardwareSPI.o: $(RADIOHEADBASE)/RHHardwareSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHSPIDriver.o: $(RADIOHEADBASE)/RHSPIDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericDriver.o: $(RADIOHEADBASE)/RHGenericDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericSPI.o: $(RADIOHEADBASE)/RHGenericSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
rf95_reliable_datagram_client: rf95_reliable_datagram_client.o RH_RF95.o RHReliableDatagram.o RHDatagram.o RasPi.o RHHardwareSPI.o RHSPIDriver.o RHGenericDriver.o RHGenericSPI.o
$(CC) $^ $(LIBS) -o rf95_reliable_datagram_client
clean:
rm -rf *.o rf95_reliable_datagram_client

View File

@@ -0,0 +1,141 @@
// rf95_reliable_datagram_client.cpp
// -*- mode: C++ -*-
// Example app showing how to create a simple addressed, reliable messaging client
// with the RHReliableDatagram class, using the RH_RF95 driver to control a RF95 radio.
// It is designed to work with the other example rf95_reliable_datagram_server.
//
// Requires Pigpio GPIO library. Install by downloading and compiling from
// http://abyz.me.uk/rpi/pigpio/, or install via command line with
// "sudo apt install pigpio". To use, run "make" at the command line in
// the folder where this source code resides. Then execute application with
// sudo ./rf95_reliable_datagram_client.
// Tested on Raspberry Pi Zero and Zero W with LoRaWan/TTN RPI Zero Shield
// by ElectronicTricks. Although this application builds and executes on
// Raspberry Pi 3, there seems to be missed messages and hangs.
// Strategically adding delays does seem to help in some cases.
//(9/20/2019) Contributed by Brody M. Based off rf22_reliable_datagram_client.pde.
// Raspberry Pi mods influenced by nrf24 example by Mike Poublon,
// and Charles-Henri Hallard (https://github.com/hallard/RadioHead)
#include <pigpio.h>
#include <stdio.h>
#include <signal.h>
#include <unistd.h>
#include <RHReliableDatagram.h>
#include <RH_RF95.h>
//Function Definitions
void sig_handler(int sig);
//Pin Definitions
#define RFM95_CS_PIN 8
#define RFM95_IRQ_PIN 25
#define RFM95_LED 4
//Client and Server Addresses
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
//RFM95 Configuration
#define RFM95_FREQUENCY 915.00
#define RFM95_TXPOWER 14
// Singleton instance of the radio driver
RH_RF95 rf95(RFM95_CS_PIN, RFM95_IRQ_PIN);
// Class to manage message delivery and receipt, using the driver declared above
RHReliableDatagram manager(rf95, CLIENT_ADDRESS);
//Flag for Ctrl-C
int flag = 0;
//Main Function
int main (int argc, const char* argv[] )
{
if (gpioInitialise()<0)
{
printf( "\n\nRPI rf95_reliable_datagram_client startup Failed.\n" );
return 1;
}
gpioSetSignalFunc(2, sig_handler); //2 is SIGINT. Ctrl+C will cause signal.
printf( "\nRPI rf95_reliable_datagram_client startup OK.\n" );
printf( "\nRPI GPIO settings:\n" );
printf("CS-> GPIO %d\n", (uint8_t) RFM95_CS_PIN);
printf("IRQ-> GPIO %d\n", (uint8_t) RFM95_IRQ_PIN);
#ifdef RFM95_LED
gpioSetMode(RFM95_LED, PI_OUTPUT);
printf("\nINFO: LED on GPIO %d\n", (uint8_t) RFM95_LED);
gpioWrite(RFM95_LED, PI_ON);
gpioDelay(500000);
gpioWrite(RFM95_LED, PI_OFF);
#endif
if (!rf95.init())
{
printf( "\n\nRF95 Driver Failed to initialize.\n\n" );
return 1;
}
/* Begin Manager/Driver settings code */
printf("\nRFM 95 Settings:\n");
printf("Frequency= %d MHz\n", (uint16_t) RFM95_FREQUENCY);
printf("Power= %d\n", (uint8_t) RFM95_TXPOWER);
printf("Client(This) Address= %d\n", CLIENT_ADDRESS);
printf("Server Address= %d\n", SERVER_ADDRESS);
rf95.setTxPower(RFM95_TXPOWER, false);
rf95.setFrequency(RFM95_FREQUENCY);
rf95.setThisAddress(CLIENT_ADDRESS);
rf95.setHeaderFrom(CLIENT_ADDRESS);
rf95.setHeaderTo(SERVER_ADDRESS);
/* End Manager/Driver settings code */
/* Begin Datagram Client Code */
uint8_t data[] = "Hello World!";
// Dont put this on the stack:
uint8_t buf[RH_RF95_MAX_MESSAGE_LEN];
while(!flag)
{
Serial.println("Sending to rf95_reliable_datagram_server");
// Send a message to manager_server
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_ON);
#endif
if (manager.sendtoWait(data, sizeof(data), SERVER_ADDRESS))
{
// Now wait for a reply from the server
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAckTimeout(buf, &len, 2000, &from))
{
Serial.print("got reply from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
}
else
{
Serial.println("No reply, is rf95_reliable_datagram_server running?");
}
}
else
Serial.println("sendtoWait failed");
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_OFF);
#endif
gpioDelay(500000);
}
printf( "\nrf95_reliable_datagram_client Tester Ending\n" );
gpioTerminate();
return 0;
}
void sig_handler(int sig)
{
flag=1;
}

View File

@@ -0,0 +1,46 @@
# Makefile
# Example for RH_RF95 on Raspberry Pi
# Requires pigpio to be installed: http://abyz.me.uk/rpi/pigpio/
CC = g++
CFLAGS = -DRASPBERRY_PI -pthread
LIBS = -lpigpio -lrt
RADIOHEADBASE = ../../../..
INCLUDE = -I$(RADIOHEADBASE)
all: rf95_reliable_datagram_server
RasPi.o: $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp
$(CC) $(CFLAGS) -c $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp $(INCLUDE)
rf95_reliable_datagram_server.o: rf95_reliable_datagram_server.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RH_RF95.o: $(RADIOHEADBASE)/RH_RF95.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHReliableDatagram.o: $(RADIOHEADBASE)/RHReliableDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHDatagram.o: $(RADIOHEADBASE)/RHDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHHardwareSPI.o: $(RADIOHEADBASE)/RHHardwareSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHSPIDriver.o: $(RADIOHEADBASE)/RHSPIDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericDriver.o: $(RADIOHEADBASE)/RHGenericDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericSPI.o: $(RADIOHEADBASE)/RHGenericSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
rf95_reliable_datagram_server: rf95_reliable_datagram_server.o RH_RF95.o RHReliableDatagram.o RHDatagram.o RasPi.o RHHardwareSPI.o RHSPIDriver.o RHGenericDriver.o RHGenericSPI.o
$(CC) $^ $(LIBS) -o rf95_reliable_datagram_server
clean:
rm -rf *.o rf95_reliable_datagram_server

View File

@@ -0,0 +1,136 @@
// rf95_reliable_datagram_server.cpp
// -*- mode: C++ -*-
// Example app showing how to create a simple addressed, reliable messaging server
// with the RHReliableDatagram class, using the RH_RF95 driver to control a RF95 radio.
// It is designed to work with the other example rf95_reliable_datagram_client.
//
// Requires Pigpio GPIO library. Install by downloading and compiling from
// http://abyz.me.uk/rpi/pigpio/, or install via command line with
// "sudo apt install pigpio". To use, run "make" at the command line in
// the folder where this source code resides. Then execute application with
// sudo ./rf95_reliable_datagram_server.
// Tested on Raspberry Pi Zero and Zero W with LoRaWan/TTN RPI Zero Shield
// by ElectronicTricks. Although this application builds and executes on
// Raspberry Pi 3, there seems to be missed messages and hangs.
// Strategically adding delays does seem to help in some cases.
//(9/20/2019) Contributed by Brody M. Based off rf22_reliable_datagram_server.pde.
// Raspberry Pi mods influenced by nrf24 example by Mike Poublon,
// and Charles-Henri Hallard (https://github.com/hallard/RadioHead)
#include <pigpio.h>
#include <stdio.h>
#include <signal.h>
#include <unistd.h>
#include <RHReliableDatagram.h>
#include <RH_RF95.h>
//Function Definitions
void sig_handler(int sig);
//Pin Definitions
#define RFM95_CS_PIN 8
#define RFM95_IRQ_PIN 25
#define RFM95_LED 4
//Client and Server Addresses
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
//RFM95 Configuration
#define RFM95_FREQUENCY 915.00
#define RFM95_TXPOWER 14
// Singleton instance of the radio driver
RH_RF95 rf95(RFM95_CS_PIN, RFM95_IRQ_PIN);
// Class to manage message delivery and receipt, using the driver declared above
RHReliableDatagram manager(rf95, SERVER_ADDRESS);
//Flag for Ctrl-C
int flag = 0;
//Main Function
int main (int argc, const char* argv[] )
{
if (gpioInitialise()<0)
{
printf( "\n\nRPI rf95_reliable_datagram_server startup Failed.\n" );
return 1;
}
gpioSetSignalFunc(2, sig_handler); //2 is SIGINT. Ctrl+C will cause signal.
printf( "\nRPI rf95_reliable_datagram_server startup OK.\n" );
printf( "\nRPI GPIO settings:\n" );
printf("CS-> GPIO %d\n", (uint8_t) RFM95_CS_PIN);
printf("IRQ-> GPIO %d\n", (uint8_t) RFM95_IRQ_PIN);
#ifdef RFM95_LED
gpioSetMode(RFM95_LED, PI_OUTPUT);
printf("\nINFO: LED on GPIO %d\n", (uint8_t) RFM95_LED);
gpioWrite(RFM95_LED, PI_ON);
gpioDelay(500000);
gpioWrite(RFM95_LED, PI_OFF);
#endif
if (!rf95.init())
{
printf( "\n\nRF95 Driver Failed to initialize.\n\n" );
return 1;
}
/* Begin Manager/Driver settings code */
printf("\nRFM 95 Settings:\n");
printf("Frequency= %d MHz\n", (uint16_t) RFM95_FREQUENCY);
printf("Power= %d\n", (uint8_t) RFM95_TXPOWER);
printf("Client Address= %d\n", CLIENT_ADDRESS);
printf("Server(This) Address= %d\n", SERVER_ADDRESS);
rf95.setTxPower(RFM95_TXPOWER, false);
rf95.setFrequency(RFM95_FREQUENCY);
rf95.setThisAddress(SERVER_ADDRESS);
rf95.setHeaderFrom(SERVER_ADDRESS);
/* End Manager/Driver settings code */
/* Begin Reliable Datagram Server Code */
uint8_t data[] = "And hello back to you";
// Dont put this on the stack:
uint8_t buf[RH_RF95_MAX_MESSAGE_LEN];
while(!flag)
{
if (manager.available())
{
// Wait for a message addressed to us from the client
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_ON);
#endif
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
// Send a reply back to the originator client
if (!manager.sendtoWait(data, sizeof(data), from))
Serial.println("sendtoWait failed");
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_OFF);
#endif
}
}
}
printf( "\nrf95_reliable_datagram_server Tester Ending\n" );
gpioTerminate();
return 0;
}
void sig_handler(int sig)
{
flag=1;
}

View File

@@ -0,0 +1,49 @@
# Makefile
# Example for RH_RF95 on Raspberry Pi
# Requires pigpio to be installed: http://abyz.me.uk/rpi/pigpio/
CC = g++
CFLAGS = -DRASPBERRY_PI -pthread
LIBS = -lpigpio -lrt
RADIOHEADBASE = ../../../..
INCLUDE = -I$(RADIOHEADBASE)
all: rf95_router_client
RasPi.o: $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp
$(CC) $(CFLAGS) -c $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp $(INCLUDE)
rf95_router_client.o: rf95_router_client.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RH_RF95.o: $(RADIOHEADBASE)/RH_RF95.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHRouter.o: $(RADIOHEADBASE)/RHRouter.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHReliableDatagram.o: $(RADIOHEADBASE)/RHReliableDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHDatagram.o: $(RADIOHEADBASE)/RHDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHHardwareSPI.o: $(RADIOHEADBASE)/RHHardwareSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHSPIDriver.o: $(RADIOHEADBASE)/RHSPIDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericDriver.o: $(RADIOHEADBASE)/RHGenericDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericSPI.o: $(RADIOHEADBASE)/RHGenericSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
rf95_router_client: rf95_router_client.o RH_RF95.o RHRouter.o RHReliableDatagram.o RHDatagram.o RasPi.o RHHardwareSPI.o RHSPIDriver.o RHGenericDriver.o RHGenericSPI.o
$(CC) $^ $(LIBS) -o rf95_router_client
clean:
rm -rf *.o rf95_router_client

View File

@@ -0,0 +1,155 @@
// rf95_router_client.cpp
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, routed reliable messaging client
// with the RHRouter class.
// It is designed to work with the other examples rf95_router_server*.
//
// Requires Pigpio GPIO library. Install by downloading and compiling from
// http://abyz.me.uk/rpi/pigpio/, or install via command line with
// "sudo apt install pigpio". To use, run "make" at the command line in
// the folder where this source code resides. Then execute application with
// sudo ./rf95_router_client.
// Tested on Raspberry Pi Zero and Zero W with LoRaWan/TTN RPI Zero Shield
// by ElectronicTricks. Although this application builds and executes on
// Raspberry Pi 3, there seems to be missed messages and hangs.
// Strategically adding delays does seem to help in some cases.
//(9/20/2019) Contributed by Brody M. Based off rf22_router_client.pde.
// Raspberry Pi mods influenced by nrf24 example by Mike Poublon,
// and Charles-Henri Hallard (https://github.com/hallard/RadioHead)
#include <pigpio.h>
#include <stdio.h>
#include <signal.h>
#include <unistd.h>
#include <RHRouter.h>
#include <RH_RF95.h>
//Function Definitions
void sig_handler(int sig);
//Pin Definitions
#define RFM95_CS_PIN 8
#define RFM95_IRQ_PIN 25
#define RFM95_LED 4
// In this small artifical network of 4 nodes,
// messages are routed via intermediate nodes to their destination
// node. All nodes can act as routers
// CLIENT_ADDRESS <-> SERVER1_ADDRESS <-> SERVER2_ADDRESS<->SERVER3_ADDRESS
#define CLIENT_ADDRESS 1
#define SERVER1_ADDRESS 2
#define SERVER2_ADDRESS 3
#define SERVER3_ADDRESS 4
//RFM95 Configuration
#define RFM95_FREQUENCY 915.00
#define RFM95_TXPOWER 14
// Create an instance of a driver
RH_RF95 rf95(RFM95_CS_PIN, RFM95_IRQ_PIN);
// Class to manage message delivery and receipt, using the driver declared above
RHRouter manager(rf95, CLIENT_ADDRESS);
//Flag for Ctrl-C
int flag = 0;
//Main Function
int main (int argc, const char* argv[] )
{
if (gpioInitialise()<0)
{
printf( "\n\nRPI rf95_router_client startup Failed.\n" );
return 1;
}
gpioSetSignalFunc(2, sig_handler); //2 is SIGINT. Ctrl+C will cause signal.
printf( "\nRPI rf95_router_client startup OK.\n" );
#ifdef RFM95_LED
gpioSetMode(RFM95_LED, PI_OUTPUT);
printf("\nINFO: LED on GPIO %d\n", (uint8_t) RFM95_LED);
gpioWrite(RFM95_LED, PI_ON);
gpioDelay(500000);
gpioWrite(RFM95_LED, PI_OFF);
#endif
if (!manager.init())
{
printf( "\n\nRouter Manager Failed to initialize.\n\n" );
return 1;
}
/* Begin Manager/Driver settings code */
printf("\nRFM 95 Settings:\n");
printf("Frequency= %d MHz\n", (uint16_t) RFM95_FREQUENCY);
printf("Power= %d\n", (uint8_t) RFM95_TXPOWER);
printf("Client(This) Address= %d\n", CLIENT_ADDRESS);
printf("Server Address 1= %d\n", SERVER1_ADDRESS);
printf("Server Address 2= %d\n", SERVER2_ADDRESS);
printf("Server Address 3= %d\n", SERVER3_ADDRESS);
printf("Route: Client-> Server 1-> Server 2-> Server 3\n");
rf95.setTxPower(RFM95_TXPOWER, false);
rf95.setFrequency(RFM95_FREQUENCY);
// Manually define the routes for this network
manager.addRouteTo(SERVER1_ADDRESS, SERVER1_ADDRESS);
manager.addRouteTo(SERVER2_ADDRESS, SERVER2_ADDRESS);
manager.addRouteTo(SERVER3_ADDRESS, SERVER3_ADDRESS);
/* End Manager/Driver settings code */
uint8_t data[] = "Hello World!";
// Dont put this on the stack:
uint8_t buf[RH_ROUTER_MAX_MESSAGE_LEN];
while(!flag)
{
Serial.println("Sending to rf95_router_server3");
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_ON);
#endif
// Send a message to a rf95_router_server
// It will be routed by the intermediate
// nodes to the destination node, accorinding to the
// routing tables in each node
if (manager.sendtoWait(data, sizeof(data), SERVER3_ADDRESS) == RH_ROUTER_ERROR_NONE)
{
// It has been reliably delivered to the next node.
// Now wait for a reply from the ultimate server
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAckTimeout(buf, &len, 3000, &from))
{
Serial.print("got reply from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
}
else
{
Serial.println("No reply, is rf95_router_server1, rf95_router_server2 and rf95_router_server3 running?");
}
}
else
Serial.println("sendtoWait failed. Are the intermediate router servers running?");
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_OFF);
#endif
gpioDelay(500000);
}
printf( "\nrf95_router_client Tester Ending\n" );
gpioTerminate();
return 0;
}
void sig_handler(int sig)
{
flag=1;
}

View File

@@ -0,0 +1,49 @@
# Makefile
# Example for RH_RF95 on Raspberry Pi
# Requires pigpio to be installed: http://abyz.me.uk/rpi/pigpio/
CC = g++
CFLAGS = -DRASPBERRY_PI -pthread
LIBS = -lpigpio -lrt
RADIOHEADBASE = ../../../..
INCLUDE = -I$(RADIOHEADBASE)
all: rf95_router_server1
RasPi.o: $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp
$(CC) $(CFLAGS) -c $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp $(INCLUDE)
rf95_router_server1.o: rf95_router_server1.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RH_RF95.o: $(RADIOHEADBASE)/RH_RF95.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHRouter.o: $(RADIOHEADBASE)/RHRouter.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHReliableDatagram.o: $(RADIOHEADBASE)/RHReliableDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHDatagram.o: $(RADIOHEADBASE)/RHDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHHardwareSPI.o: $(RADIOHEADBASE)/RHHardwareSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHSPIDriver.o: $(RADIOHEADBASE)/RHSPIDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericDriver.o: $(RADIOHEADBASE)/RHGenericDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericSPI.o: $(RADIOHEADBASE)/RHGenericSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
rf95_router_server1: rf95_router_server1.o RH_RF95.o RHRouter.o RHReliableDatagram.o RHDatagram.o RasPi.o RHHardwareSPI.o RHSPIDriver.o RHGenericDriver.o RHGenericSPI.o
$(CC) $^ $(LIBS) -o rf95_router_server1
clean:
rm -rf *.o rf95_router_server1

View File

@@ -0,0 +1,143 @@
// rf95_router_server1.cpp
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, routed reliable messaging server
// with the RHRouter class.
// It is designed to work with the other example rf95_router_client.
//
// Requires Pigpio GPIO library. Install by downloading and compiling from
// http://abyz.me.uk/rpi/pigpio/, or install via command line with
// "sudo apt install pigpio". To use, run "make" at the command line in
// the folder where this source code resides. Then execute application with
// sudo ./rf95_router_server1.
// Tested on Raspberry Pi Zero and Zero W with LoRaWan/TTN RPI Zero Shield
// by ElectronicTricks. Although this application builds and executes on
// Raspberry Pi 3, there seems to be missed messages and hangs.
// Strategically adding delays does seem to help in some cases.
//(9/20/2019) Contributed by Brody M. Based off rf22_router_server1.pde.
// Raspberry Pi mods influenced by nrf24 example by Mike Poublon,
// and Charles-Henri Hallard (https://github.com/hallard/RadioHead)
#include <pigpio.h>
#include <stdio.h>
#include <signal.h>
#include <unistd.h>
#include <RHRouter.h>
#include <RH_RF95.h>
//Function Definitions
void sig_handler(int sig);
//Pin Definitions
#define RFM95_CS_PIN 8
#define RFM95_IRQ_PIN 25
#define RFM95_LED 4
// In this small artifical network of 4 nodes,
// messages are routed via intermediate nodes to their destination
// node. All nodes can act as routers
// CLIENT_ADDRESS <-> SERVER1_ADDRESS <-> SERVER2_ADDRESS<->SERVER3_ADDRESS
#define CLIENT_ADDRESS 1
#define SERVER1_ADDRESS 2
#define SERVER2_ADDRESS 3
#define SERVER3_ADDRESS 4
//RFM95 Configuration
#define RFM95_FREQUENCY 915.00
#define RFM95_TXPOWER 14
// Create an instance of a driver
RH_RF95 rf95(RFM95_CS_PIN, RFM95_IRQ_PIN);
// Class to manage message delivery and receipt, using the driver declared above
RHRouter manager(rf95, SERVER1_ADDRESS);
//Flag for Ctrl-C
int flag = 0;
//Main Function
int main (int argc, const char* argv[] )
{
if (gpioInitialise()<0)
{
printf( "\n\nRPI rf95_router_server1 startup Failed.\n" );
return 1;
}
gpioSetSignalFunc(2, sig_handler); //2 is SIGINT. Ctrl+C will cause signal.
printf( "\nRPI rf95_router_server1 startup OK.\n" );
#ifdef RFM95_LED
gpioSetMode(RFM95_LED, PI_OUTPUT);
printf("\nINFO: LED on GPIO %d\n", (uint8_t) RFM95_LED);
gpioWrite(RFM95_LED, PI_ON);
gpioDelay(500000);
gpioWrite(RFM95_LED, PI_OFF);
#endif
if (!manager.init())
{
printf( "\n\nRouter Manager Failed to initialize.\n\n" );
return 1;
}
/* Begin Manager/Driver settings code */
printf("\nRFM 95 Settings:\n");
printf("Frequency= %d MHz\n", (uint16_t) RFM95_FREQUENCY);
printf("Power= %d\n", (uint8_t) RFM95_TXPOWER);
printf("Client Address= %d\n", CLIENT_ADDRESS);
printf("Server(This) Address 1= %d\n", SERVER1_ADDRESS);
printf("Server Address 2= %d\n", SERVER2_ADDRESS);
printf("Server Address 3= %d\n", SERVER3_ADDRESS);
printf("Route: Client-> Server 1-> Server 2-> Server 3\n");
rf95.setTxPower(RFM95_TXPOWER, false);
rf95.setFrequency(RFM95_FREQUENCY);
rf95.setThisAddress(SERVER1_ADDRESS);
// Manually define the routes for this network
manager.addRouteTo(CLIENT_ADDRESS, CLIENT_ADDRESS);
manager.addRouteTo(SERVER2_ADDRESS, SERVER2_ADDRESS);
manager.addRouteTo(SERVER3_ADDRESS, SERVER2_ADDRESS);
/* End Manager/Driver settings code */
uint8_t data[] = "And hello back to you from server1";
// Dont put this on the stack:
uint8_t buf[RH_ROUTER_MAX_MESSAGE_LEN];
while(!flag)
{
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_ON);
#endif
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
// Send a reply back to the originator client
if (manager.sendtoWait(data, sizeof(data), from) != RH_ROUTER_ERROR_NONE)
Serial.println("sendtoWait failed");
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_OFF);
#endif
}
}
printf( "\nrf95_router_server1 Tester Ending\n" );
gpioTerminate();
return 0;
}
void sig_handler(int sig)
{
flag=1;
}

View File

@@ -0,0 +1,49 @@
# Makefile
# Example for RH_RF95 on Raspberry Pi
# Requires pigpio to be installed: http://abyz.me.uk/rpi/pigpio/
CC = g++
CFLAGS = -DRASPBERRY_PI -pthread
LIBS = -lpigpio -lrt
RADIOHEADBASE = ../../../..
INCLUDE = -I$(RADIOHEADBASE)
all: rf95_router_server2
RasPi.o: $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp
$(CC) $(CFLAGS) -c $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp $(INCLUDE)
rf95_router_server2.o: rf95_router_server2.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RH_RF95.o: $(RADIOHEADBASE)/RH_RF95.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHRouter.o: $(RADIOHEADBASE)/RHRouter.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHReliableDatagram.o: $(RADIOHEADBASE)/RHReliableDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHDatagram.o: $(RADIOHEADBASE)/RHDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHHardwareSPI.o: $(RADIOHEADBASE)/RHHardwareSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHSPIDriver.o: $(RADIOHEADBASE)/RHSPIDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericDriver.o: $(RADIOHEADBASE)/RHGenericDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericSPI.o: $(RADIOHEADBASE)/RHGenericSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
rf95_router_server2: rf95_router_server2.o RH_RF95.o RHRouter.o RHReliableDatagram.o RHDatagram.o RasPi.o RHHardwareSPI.o RHSPIDriver.o RHGenericDriver.o RHGenericSPI.o
$(CC) $^ $(LIBS) -o rf95_router_server2
clean:
rm -rf *.o rf95_router_server2

View File

@@ -0,0 +1,143 @@
// rf95_router_server2.cpp
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, routed reliable messaging server
// with the RHRouter class.
// It is designed to work with the other example rf95_router_client.
//
// Requires Pigpio GPIO library. Install by downloading and compiling from
// http://abyz.me.uk/rpi/pigpio/, or install via command line with
// "sudo apt install pigpio". To use, run "make" at the command line in
// the folder where this source code resides. Then execute application with
// sudo ./rf95_router_server2.
// Tested on Raspberry Pi Zero and Zero W with LoRaWan/TTN RPI Zero Shield
// by ElectronicTricks. Although this application builds and executes on
// Raspberry Pi 3, there seems to be missed messages and hangs.
// Strategically adding delays does seem to help in some cases.
//(9/20/2019) Contributed by Brody M. Based off rf22_router_server2.pde.
// Raspberry Pi mods influenced by nrf24 example by Mike Poublon,
// and Charles-Henri Hallard (https://github.com/hallard/RadioHead)
#include <pigpio.h>
#include <stdio.h>
#include <signal.h>
#include <unistd.h>
#include <RHRouter.h>
#include <RH_RF95.h>
//Function Definitions
void sig_handler(int sig);
//Pin Definitions
#define RFM95_CS_PIN 8
#define RFM95_IRQ_PIN 25
#define RFM95_LED 4
// In this small artifical network of 4 nodes,
// messages are routed via intermediate nodes to their destination
// node. All nodes can act as routers
// CLIENT_ADDRESS <-> SERVER1_ADDRESS <-> SERVER2_ADDRESS<->SERVER3_ADDRESS
#define CLIENT_ADDRESS 1
#define SERVER1_ADDRESS 2
#define SERVER2_ADDRESS 3
#define SERVER3_ADDRESS 4
//RFM95 Configuration
#define RFM95_FREQUENCY 915.00
#define RFM95_TXPOWER 14
// Create an instance of a driver
RH_RF95 rf95(RFM95_CS_PIN, RFM95_IRQ_PIN);
// Class to manage message delivery and receipt, using the driver declared above
RHRouter manager(rf95, SERVER2_ADDRESS);
//Flag for Ctrl-C
int flag = 0;
//Main Function
int main (int argc, const char* argv[] )
{
if (gpioInitialise()<0)
{
printf( "\n\nRPI rf95_router_server2 startup Failed.\n" );
return 1;
}
gpioSetSignalFunc(2, sig_handler); //2 is SIGINT. Ctrl+C will cause signal.
printf( "\nRPI rf95_router_server2 startup OK.\n" );
#ifdef RFM95_LED
gpioSetMode(RFM95_LED, PI_OUTPUT);
printf("\nINFO: LED on GPIO %d\n", (uint8_t) RFM95_LED);
gpioWrite(RFM95_LED, PI_ON);
gpioDelay(500000);
gpioWrite(RFM95_LED, PI_OFF);
#endif
if (!manager.init())
{
printf( "\n\nRouter Manager Failed to initialize.\n\n" );
return 1;
}
/* Begin Manager/Driver settings code */
printf("\nRFM 95 Settings:\n");
printf("Frequency= %d MHz\n", (uint16_t) RFM95_FREQUENCY);
printf("Power= %d\n", (uint8_t) RFM95_TXPOWER);
printf("Client Address= %d\n", CLIENT_ADDRESS);
printf("Server Address 1 = %d\n", SERVER1_ADDRESS);
printf("Server(This) Address 2 = %d\n", SERVER2_ADDRESS);
printf("Server Address 3= %d\n", SERVER3_ADDRESS);
printf("Route: Client-> Server 1-> Server 2-> Server 3\n");
rf95.setTxPower(RFM95_TXPOWER, false);
rf95.setFrequency(RFM95_FREQUENCY);
rf95.setThisAddress(SERVER2_ADDRESS);
// Manually define the routes for this network
manager.addRouteTo(CLIENT_ADDRESS, CLIENT_ADDRESS);
manager.addRouteTo(SERVER2_ADDRESS, SERVER2_ADDRESS);
manager.addRouteTo(SERVER3_ADDRESS, SERVER2_ADDRESS);
/* End Manager/Driver settings code */
uint8_t data[] = "And hello back to you from server2";
// Dont put this on the stack:
uint8_t buf[RH_ROUTER_MAX_MESSAGE_LEN];
while(!flag)
{
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_ON);
#endif
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
// Send a reply back to the originator client
if (manager.sendtoWait(data, sizeof(data), from) != RH_ROUTER_ERROR_NONE)
Serial.println("sendtoWait failed");
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_OFF);
#endif
}
}
printf( "\nrf95_router_server2 Tester Ending\n" );
gpioTerminate();
return 0;
}
void sig_handler(int sig)
{
flag=1;
}

View File

@@ -0,0 +1,49 @@
# Makefile
# Example for RH_RF95 on Raspberry Pi
# Requires pigpio to be installed: http://abyz.me.uk/rpi/pigpio/
CC = g++
CFLAGS = -DRASPBERRY_PI -pthread
LIBS = -lpigpio -lrt
RADIOHEADBASE = ../../../..
INCLUDE = -I$(RADIOHEADBASE)
all: rf95_router_server3
RasPi.o: $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp
$(CC) $(CFLAGS) -c $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp $(INCLUDE)
rf95_router_server3.o: rf95_router_server3.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RH_RF95.o: $(RADIOHEADBASE)/RH_RF95.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHRouter.o: $(RADIOHEADBASE)/RHRouter.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHReliableDatagram.o: $(RADIOHEADBASE)/RHReliableDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHDatagram.o: $(RADIOHEADBASE)/RHDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHHardwareSPI.o: $(RADIOHEADBASE)/RHHardwareSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHSPIDriver.o: $(RADIOHEADBASE)/RHSPIDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericDriver.o: $(RADIOHEADBASE)/RHGenericDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericSPI.o: $(RADIOHEADBASE)/RHGenericSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
rf95_router_server3: rf95_router_server3.o RH_RF95.o RHRouter.o RHReliableDatagram.o RHDatagram.o RasPi.o RHHardwareSPI.o RHSPIDriver.o RHGenericDriver.o RHGenericSPI.o
$(CC) $^ $(LIBS) -o rf95_router_server3
clean:
rm -rf *.o rf95_router_server3

View File

@@ -0,0 +1,143 @@
// rf95_router_server3.cpp
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, routed reliable messaging server
// with the RHRouter class.
// It is designed to work with the other example rf95_router_client.
//
// Requires Pigpio GPIO library. Install by downloading and compiling from
// http://abyz.me.uk/rpi/pigpio/, or install via command line with
// "sudo apt install pigpio". To use, run "make" at the command line in
// the folder where this source code resides. Then execute application with
// sudo ./rf95_router_server3.
// Tested on Raspberry Pi Zero and Zero W with LoRaWan/TTN RPI Zero Shield
// by ElectronicTricks. Although this application builds and executes on
// Raspberry Pi 3, there seems to be missed messages and hangs.
// Strategically adding delays does seem to help in some cases.
//(9/20/2019) Contributed by Brody M. Based off rf22_router_server3.pde.
// Raspberry Pi mods influenced by nrf24 example by Mike Poublon,
// and Charles-Henri Hallard (https://github.com/hallard/RadioHead)
#include <pigpio.h>
#include <stdio.h>
#include <signal.h>
#include <unistd.h>
#include <RHRouter.h>
#include <RH_RF95.h>
//Function Definitions
void sig_handler(int sig);
//Pin Definitions
#define RFM95_CS_PIN 8
#define RFM95_IRQ_PIN 25
#define RFM95_LED 4
// In this small artifical network of 4 nodes,
// messages are routed via intermediate nodes to their destination
// node. All nodes can act as routers
// CLIENT_ADDRESS <-> SERVER1_ADDRESS <-> SERVER2_ADDRESS<->SERVER3_ADDRESS
#define CLIENT_ADDRESS 1
#define SERVER1_ADDRESS 2
#define SERVER2_ADDRESS 3
#define SERVER3_ADDRESS 4
//RFM95 Configuration
#define RFM95_FREQUENCY 915.00
#define RFM95_TXPOWER 14
// Create an instance of a driver
RH_RF95 rf95(RFM95_CS_PIN, RFM95_IRQ_PIN);
// Class to manage message delivery and receipt, using the driver declared above
RHRouter manager(rf95, SERVER3_ADDRESS);
//Flag for Ctrl-C
int flag = 0;
//Main Function
int main (int argc, const char* argv[] )
{
if (gpioInitialise()<0)
{
printf( "\n\nRPI rf95_router_server3 startup Failed.\n" );
return 1;
}
gpioSetSignalFunc(2, sig_handler); //2 is SIGINT. Ctrl+C will cause signal.
printf( "\nRPI rf95_router_server3 startup OK.\n" );
#ifdef RFM95_LED
gpioSetMode(RFM95_LED, PI_OUTPUT);
printf("\nINFO: LED on GPIO %d\n", (uint8_t) RFM95_LED);
gpioWrite(RFM95_LED, PI_ON);
gpioDelay(500000);
gpioWrite(RFM95_LED, PI_OFF);
#endif
if (!manager.init())
{
printf( "\n\nRouter Manager Failed to initialize.\n\n" );
return 1;
}
/* Begin Manager/Driver settings code */
printf("\nRFM 95 Settings:\n");
printf("Frequency= %d MHz\n", (uint16_t) RFM95_FREQUENCY);
printf("Power= %d\n", (uint8_t) RFM95_TXPOWER);
printf("Client Address= %d\n", CLIENT_ADDRESS);
printf("Server Address 1 = %d\n", SERVER1_ADDRESS);
printf("Server Address 2 = %d\n", SERVER2_ADDRESS);
printf("Server(This) Address 3 = %d\n", SERVER3_ADDRESS);
printf("Route: Client-> Server 1-> Server 2-> Server 3\n");
rf95.setTxPower(RFM95_TXPOWER, false);
rf95.setFrequency(RFM95_FREQUENCY);
rf95.setThisAddress(SERVER3_ADDRESS);
// Manually define the routes for this network
manager.addRouteTo(CLIENT_ADDRESS, CLIENT_ADDRESS);
manager.addRouteTo(SERVER2_ADDRESS, SERVER2_ADDRESS);
manager.addRouteTo(SERVER3_ADDRESS, SERVER2_ADDRESS);
/* End Manager/Driver settings code */
uint8_t data[] = "And hello back to you from server3";
// Dont put this on the stack:
uint8_t buf[RH_ROUTER_MAX_MESSAGE_LEN];
while(!flag)
{
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_ON);
#endif
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
// Send a reply back to the originator client
if (manager.sendtoWait(data, sizeof(data), from) != RH_ROUTER_ERROR_NONE)
Serial.println("sendtoWait failed");
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_OFF);
#endif
}
}
printf( "\nrf95_router_server3 Tester Ending\n" );
gpioTerminate();
return 0;
}
void sig_handler(int sig)
{
flag=1;
}

View File

@@ -0,0 +1,49 @@
# Makefile
# Example for RH_RF95 on Raspberry Pi
# Requires pigpio to be installed: http://abyz.me.uk/rpi/pigpio/
CC = g++
CFLAGS = -DRASPBERRY_PI -pthread
LIBS = -lpigpio -lrt
RADIOHEADBASE = ../../../..
INCLUDE = -I$(RADIOHEADBASE)
all: rf95_router_test
RasPi.o: $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp
$(CC) $(CFLAGS) -c $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp $(INCLUDE)
rf95_router_test.o: rf95_router_test.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RH_RF95.o: $(RADIOHEADBASE)/RH_RF95.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHRouter.o: $(RADIOHEADBASE)/RHRouter.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHReliableDatagram.o: $(RADIOHEADBASE)/RHReliableDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHDatagram.o: $(RADIOHEADBASE)/RHDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHHardwareSPI.o: $(RADIOHEADBASE)/RHHardwareSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHSPIDriver.o: $(RADIOHEADBASE)/RHSPIDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericDriver.o: $(RADIOHEADBASE)/RHGenericDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericSPI.o: $(RADIOHEADBASE)/RHGenericSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
rf95_router_test: rf95_router_test.o RH_RF95.o RHRouter.o RHReliableDatagram.o RHDatagram.o RasPi.o RHHardwareSPI.o RHSPIDriver.o RHGenericDriver.o RHGenericSPI.o
$(CC) $^ $(LIBS) -o rf95_router_test
clean:
rm -rf *.o rf95_router_test

View File

@@ -0,0 +1,183 @@
// rf95_router_test.cpp
// -*- mode: C++ -*-
//
// Test code used during library development, showing how
// to do various things, and how to call various functions
//
// Requires Pigpio GPIO library. Install by downloading and compiling from
// http://abyz.me.uk/rpi/pigpio/, or install via command line with
// "sudo apt install pigpio". To use, run "make" at the command line in
// the folder where this source code resides. Then execute application with
// sudo ./rf95_router_test.
// Tested on Raspberry Pi Zero and Zero W with LoRaWan/TTN RPI Zero Shield
// by ElectronicTricks. Although this application builds and executes on
// Raspberry Pi 3, there seems to be missed messages and hangs.
// Strategically adding delays does seem to help in some cases.
//(10/6/2019) Contributed by Brody M. Based off rf22_router_tester.pde.
// Raspberry Pi mods influenced by nrf24 example by Mike Poublon,
// and Charles-Henri Hallard (https://github.com/hallard/RadioHead)
#include <pigpio.h>
#include <stdio.h>
#include <signal.h>
#include <unistd.h>
#include <RHRouter.h>
#include <RH_RF95.h>
//Function Definitions
void sig_handler(int sig);
void test_tx(void);
void test_routes(void);
uint8_t data[] = "Hello World!";
// Dont put this on the stack:
//uint8_t buf[RH_RF95_MAX_MESSAGE_LEN];
//Pin Definitions
#define RFM95_CS_PIN 8
#define RFM95_IRQ_PIN 25
#define RFM95_LED 4
#define CLIENT_ADDRESS 1
#define ROUTER_ADDRESS 2
#define SERVER_ADDRESS 3
//RFM95 Configuration
#define RFM95_FREQUENCY 915.00
#define RFM95_TXPOWER 14
// Singleton instance of the radio driver
RH_RF95 rf95(RFM95_CS_PIN, RFM95_IRQ_PIN);
// Class to manage message delivery and receipt, using the driver declared above
RHRouter manager(rf95, CLIENT_ADDRESS);
//Flag for Ctrl-C
int flag = 0;
//Main Function
int main (int argc, const char* argv[] )
{
if (gpioInitialise()<0)
{
printf( "\n\nRPI rf95_router_tester startup Failed.\n" );
return 1;
}
gpioSetSignalFunc(2, sig_handler); //2 is SIGINT. Ctrl+C will cause signal.
printf( "\nRPI rf95_router_tester startup OK.\n" );
#ifdef RFM95_LED
gpioSetMode(RFM95_LED, PI_OUTPUT);
printf("\nINFO: LED on GPIO %d\n", (uint8_t) RFM95_LED);
gpioWrite(RFM95_LED, PI_ON);
gpioDelay(500000);
gpioWrite(RFM95_LED, PI_OFF);
#endif
if (!manager.init())
{
printf( "\n\nRouter Manager Failed to initialize.\n\n" );
return 1;
}
/* Begin Manager/Driver settings code */
printf("\nRFM 95 Settings:\n");
printf("Frequency= %d MHz\n", (uint16_t) RFM95_FREQUENCY);
printf("Power= %d\n", (uint8_t) RFM95_TXPOWER);
printf("Client(This) Address= %d\n", CLIENT_ADDRESS);
printf("Router Address = %d\n", ROUTER_ADDRESS);
printf("Server Address = %d\n", SERVER_ADDRESS);
rf95.setTxPower(RFM95_TXPOWER, false);
rf95.setFrequency(RFM95_FREQUENCY);
/* End Manager/Driver settings code */
while(!flag)
{
Serial.println("Running test function...");
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_ON);
#endif
// test_routes();
test_tx();
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_OFF);
#endif
gpioDelay(500000);
}
printf( "\nrf95_router_test Tester Ending\n" );
gpioTerminate();
return 0;
}
void sig_handler(int sig)
{
flag=1;
}
void test_routes()
{
manager.clearRoutingTable();
// manager.printRoutingTable();
manager.addRouteTo(1, 101);
manager.addRouteTo(2, 102);
manager.addRouteTo(3, 103);
RHRouter::RoutingTableEntry* e;
e = manager.getRouteTo(0);
if (e) // Should fail
Serial.println("getRouteTo 0 failed");
e = manager.getRouteTo(1);
if (!e)
Serial.println("getRouteTo 1 failed");
if (e->dest != 1)
Serial.println("getRouteTo 2 failed");
if (e->next_hop != 101)
Serial.println("getRouteTo 3 failed");
if (e->state != RHRouter::Valid)
Serial.println("getRouteTo 4 failed");
e = manager.getRouteTo(2);
if (!e)
Serial.println("getRouteTo 5 failed");
if (e->dest != 2)
Serial.println("getRouteTo 6 failed");
if (e->next_hop != 102)
Serial.println("getRouteTo 7 failed");
if (e->state != RHRouter::Valid)
Serial.println("getRouteTo 8 failed");
if (!manager.deleteRouteTo(1))
Serial.println("deleteRouteTo 1 failed");
// Route to 1 should now be gone
e = manager.getRouteTo(1);
if (e)
Serial.println("deleteRouteTo 2 failed");
Serial.println("-------------------");
// manager.printRoutingTable();
delay(500);
}
void test_tx()
{
manager.addRouteTo(SERVER_ADDRESS, ROUTER_ADDRESS);
uint8_t errorcode;
errorcode = manager.sendtoWait(data, sizeof(data), 100); // Should fail with no route
if (errorcode != RH_ROUTER_ERROR_NO_ROUTE)
Serial.println("sendtoWait 1 failed");
errorcode = manager.sendtoWait(data, 255, 10); // Should fail too big
if (errorcode != RH_ROUTER_ERROR_INVALID_LENGTH)
Serial.println("sendtoWait 2 failed");
errorcode = manager.sendtoWait(data, sizeof(data), SERVER_ADDRESS); // Should fail after timeouts to 110
if (errorcode != RH_ROUTER_ERROR_UNABLE_TO_DELIVER)
Serial.println("sendtoWait 3 failed");
Serial.println("-------------------");
delay(500);
}

View File

@@ -0,0 +1,84 @@
# Makefile
# Example for RH_RF95 on Raspberry Pi
# Requires pigpio to be installed: http://abyz.me.uk/rpi/pigpio/
CROSSCOMPILER=$(shell if [ -z `which 'arm-linux-gnueabihf-g++'` ]; then echo "no"; else echo "yes"; fi)
ifeq ($(CROSSCOMPILER),yes)
CC = arm-linux-gnueabihf-g++
CFLAGS = -DRASPBERRY_PI -DRH_USE_MUTEX -pthread
LIBS = -lpigpio -lrt -L$(PIGPIOBASE) -lpthread -D_REENTRANT
RADIOHEADBASE = ../../../..
PIGPIOBASE = ../../../../../pigpio/
SHARED = ../shared/
INCLUDE = -I$(RADIOHEADBASE) -I$(PIGPIOBASE) -I$(SHARED)
else
CC = g++
CFLAGS = -DRASPBERRY_PI -DRH_USE_MUTEX -pthread
LIBS = -lpigpio -lrt
RADIOHEADBASE = ../../../..
PIGPIOBASE = ../../../../../pigpio/
SHARED = ../shared/
INCLUDE = -I$(RADIOHEADBASE) -I$(PIGPIOBASE) -I$(SHARED)
endif
ifeq ($(REGION),Europe)
CFLAGS += -DEUROPE
endif
ifeq ($(LORABOARD),DraginoLoraGPSHat)
CFLAGS += -DDRAGINO_GPS_HAT
endif
ifeq ($(DEBUG),1)
CFLAGS += -g3
endif
all: rf95_server1 rf95_server2
RasPi.o: $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp
$(CC) $(CFLAGS) -c $(RADIOHEADBASE)/RHutil_pigpio/RasPi.cpp $(INCLUDE)
help_functions.o: $(SHARED)/help_functions.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
rf95_server1.o: rf95_server1.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
rf95_server2.o: rf95_server2.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RH_RF95.o: $(RADIOHEADBASE)/RH_RF95.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHDatagram.o: $(RADIOHEADBASE)/RHDatagram.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHHardwareSPI.o: $(RADIOHEADBASE)/RHHardwareSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHSPIDriver.o: $(RADIOHEADBASE)/RHSPIDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericDriver.o: $(RADIOHEADBASE)/RHGenericDriver.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
RHGenericSPI.o: $(RADIOHEADBASE)/RHGenericSPI.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
gpsMT3339.o: $(SHARED)/gpsMT3339.cpp
$(CC) $(CFLAGS) -c $(INCLUDE) $<
rf95_server1: rf95_server1.o help_functions.o RH_RF95.o RHDatagram.o RasPi.o RHHardwareSPI.o RHSPIDriver.o RHGenericDriver.o RHGenericSPI.o gpsMT3339.o
$(CC) $^ $(LIBS) -o rf95_server1
rf95_server2: rf95_server2.o help_functions.o RH_RF95.o RHDatagram.o RasPi.o RHHardwareSPI.o RHSPIDriver.o RHGenericDriver.o RHGenericSPI.o gpsMT3339.o
$(CC) $^ $(LIBS) -o rf95_server2
clean:
rm -rf *.o rf95_server1 rf95_server2
deploy: rf95_server1 rf95_server2
sshpass -p"$(PASSWD)" scp rf95_server1 pi@$(HOST):/home/pi
sshpass -p"$(PASSWD)" scp rf95_server2 pi@$(HOST):/home/pi

View File

@@ -0,0 +1,147 @@
// rf95_server.cpp
// -*- mode: C++ -*-
// Example app showing how to create a simple messageing server
// with the RH_RF95 class. RH_RF95 class does not provide for addressing or
// reliability, so you should only use RH_RF95 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example rf95_client.
//
// Requires Pigpio GPIO library. Install by downloading and compiling from
// http://abyz.me.uk/rpi/pigpio/, or install via command line with
// "sudo apt install pigpio". To use, run "make" at the command line in
// the folder where this source code resides. Then execute application with
// sudo ./rf95_server.
// Tested on Raspberry Pi Zero and Zero W with LoRaWan/TTN RPI Zero Shield
// by ElectronicTricks. Although this application builds and executes on
// Raspberry Pi 3, there seems to be missed messages and hangs.
// Strategically adding delays does seem to help in some cases.
//(9/20/2019) Contributed by Brody M. Based off rf22_server.pde.
// Raspberry Pi mods influenced by nrf24 example by Mike Poublon,
// and Charles-Henri Hallard (https://github.com/hallard/RadioHead)
#include <pigpio.h>
#include <stdio.h>
#include <signal.h>
#include <unistd.h>
#include <RH_RF95.h>
//Function Definitions
void sig_handler(int sig);
#ifdef DRAGINO_GPS_HAT
// Pin definitions for dragino gps hat
#define RFM95_CS_PIN 25 // Slave Select on GPIO25 so P1 connector pin #22
#define RFM95_IRQ_PIN 4 // IRQ on GPIO4 so P1 connector pin #7
#define RFM95_RESET_PIN 17 // Reset on GPIO17 so P1 connector pin #11
#undef RFM95_LED // Dragino Board as no LED to drive
#else
//Pin Definitions
#define RFM95_CS_PIN 8
#define RFM95_IRQ_PIN 25
#define RFM95_LED 4
#endif
//Client and Server Addresses
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
//RFM95 Configuration
#ifdef EUROPE
#define RFM95_FREQUENCY 868.00
#else
#define RFM95_FREQUENCY 915.00
#endif
#define RFM95_TXPOWER 14
// Singleton instance of the radio driver
RH_RF95 rf95(RFM95_CS_PIN, RFM95_IRQ_PIN);
//Flag for Ctrl-C
int flag = 0;
//Main Function
int main (int argc, const char* argv[] )
{
if (gpioInitialise()<0)
{
printf( "\n\nRPI rf95_server startup Failed.\n" );
return 1;
}
gpioSetSignalFunc(2, sig_handler); //2 is SIGINT. Ctrl+C will cause signal.
printf( "\nRPI rf95_server startup OK.\n" );
printf( "\nRPI GPIO settings:\n" );
printf("CS-> GPIO %d\n", (uint8_t) RFM95_CS_PIN);
printf("IRQ-> GPIO %d\n", (uint8_t) RFM95_IRQ_PIN);
#ifdef RFM95_LED
gpioSetMode(RFM95_LED, PI_OUTPUT);
printf("LED-> GPIO %d\n", (uint8_t) RFM95_LED);
gpioWrite(RFM95_LED, PI_ON);
gpioDelay(500000);
gpioWrite(RFM95_LED, PI_OFF);
#endif
if (!rf95.init())
{
printf( "\n\nRF95 Driver Failed to initialize.\n\n" );
return 1;
}
/* Begin Manager/Driver settings code */
printf("\nRFM 95 Settings:\n");
printf("Frequency= %d MHz\n", (uint16_t) RFM95_FREQUENCY);
printf("Power= %d\n", (uint8_t) RFM95_TXPOWER);
printf("Client Address= %d\n", CLIENT_ADDRESS);
printf("Server(This) Address= %d\n", SERVER_ADDRESS);
rf95.setTxPower(RFM95_TXPOWER, false);
rf95.setFrequency(RFM95_FREQUENCY);
rf95.setThisAddress(SERVER_ADDRESS);
rf95.setModemConfig(RH_RF95::Bw125Cr48Sf4096);
/* End Manager/Driver settings code */
/* Begin Datagram Server Code */
while(!flag)
{
if (rf95.available())
{
// Should be a message for us now
uint8_t buf[RH_RF95_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (rf95.recv(buf, &len))
{
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_ON);
#endif
// RF95::printBuffer("request: ", buf, len);
Serial.print("got request: ");
Serial.println((char*)buf);
// Serial.print("RSSI: ");
// Serial.println(rf95.lastRssi(), DEC);
//Send a reply
uint8_t data[] = "And hello back to you";
rf95.send(data, sizeof(data));
rf95.waitPacketSent();
Serial.println("Sent a reply");
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_OFF);
#endif
}
else
{
Serial.println("recv failed");
}
}
}
/* End Datagram Server Code */
printf( "\nrf95_server Tester Ending\n" );
gpioTerminate();
return 0;
}
void sig_handler(int sig)
{
flag=1;
}

View File

@@ -0,0 +1,195 @@
// rf95_server.cpp
// -*- mode: C++ -*-
// Example app showing how to create a simple messageing server
// with the RH_RF95 class. RH_RF95 class does not provide for addressing or
// reliability, so you should only use RH_RF95 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example rf95_client.
//
// Requires Pigpio GPIO library. Install by downloading and compiling from
// http://abyz.me.uk/rpi/pigpio/, or install via command line with
// "sudo apt install pigpio". To use, run "make" at the command line in
// the folder where this source code resides. Then execute application with
// sudo ./rf95_server.
// Tested on Raspberry Pi Zero and Zero W with LoRaWan/TTN RPI Zero Shield
// by ElectronicTricks. Although this application builds and executes on
// Raspberry Pi 3, there seems to be missed messages and hangs.
// Strategically adding delays does seem to help in some cases.
//(9/20/2019) Contributed by Brody M. Based off rf22_server.pde.
// Raspberry Pi mods influenced by nrf24 example by Mike Poublon,
// and Charles-Henri Hallard (https://github.com/hallard/RadioHead)
#include <pigpio.h>
#include <stdio.h>
#include <signal.h>
#include <unistd.h>
#include <RH_RF95.h>
#include <help_functions.h>
//Function Definitions
void sig_handler(int sig);
#ifdef DRAGINO_GPS_HAT
pthread_mutex_t gps_data_mutex;
#include <gpsMT3339.h>
// Pin definitions for dragino gps hat
#define RFM95_CS_PIN 25 // Slave Select on GPIO25 so P1 connector pin #22
#define RFM95_IRQ_PIN 4 // IRQ on GPIO4 so P1 connector pin #7
#define RFM95_RESET_PIN 17 // Reset on GPIO17 so P1 connector pin #11
#undef RFM95_LED // Dragino Board as no LED to drive
#else
//Pin Definitions
#define RFM95_CS_PIN 8
#define RFM95_IRQ_PIN 25
#define RFM95_LED 4
#endif
//Client and Server Addresses
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
//RFM95 Configuration
#ifdef EUROPE
#define RFM95_FREQUENCY 868.00
#else
#define RFM95_FREQUENCY 915.00
#endif
#define RFM95_TXPOWER 14
// Singleton instance of the radio driver
RH_RF95 rf95(RFM95_CS_PIN, RFM95_IRQ_PIN);
#ifdef DRAGINO_GPS_HAT
gps_MT3339 gps(GPS_DEVICE, &gps_data_mutex);
#endif
//Flag for Ctrl-C
int flag = 0;
//Main Function
int main (int argc, const char* argv[] )
{
if (gpioInitialise()<0)
{
printf( "\n\nRPI rf95_server startup Failed.\n" );
return 1;
}
gpioSetSignalFunc(2, sig_handler); //2 is SIGINT. Ctrl+C will cause signal.
printf( "\nRPI rf95_server startup OK.\n" );
printf( "\nRPI GPIO settings:\n" );
printf("CS-> GPIO %d\n", (uint8_t) RFM95_CS_PIN);
printf("IRQ-> GPIO %d\n", (uint8_t) RFM95_IRQ_PIN);
#ifdef RFM95_LED
gpioSetMode(RFM95_LED, PI_OUTPUT);
printf("LED-> GPIO %d\n", (uint8_t) RFM95_LED);
gpioWrite(RFM95_LED, PI_ON);
gpioDelay(500000);
gpioWrite(RFM95_LED, PI_OFF);
#endif
if (!rf95.init())
{
printf( "\n\nRF95 Driver Failed to initialize.\n\n" );
return 1;
}
/* Begin Manager/Driver settings code */
printf("\nRFM 95 Settings:\n");
printf("Frequency= %d MHz\n", (uint16_t) RFM95_FREQUENCY);
printf("Power= %d\n", (uint8_t) RFM95_TXPOWER);
printf("Client Address= %d\n", CLIENT_ADDRESS);
printf("Server(This) Address= %d\n", SERVER_ADDRESS);
rf95.setTxPower(RFM95_TXPOWER, false);
rf95.setFrequency(RFM95_FREQUENCY);
rf95.setThisAddress(SERVER_ADDRESS);
rf95.setModemConfig(RH_RF95::Bw125Cr48Sf4096);
/* End Manager/Driver settings code */
rf95.printRegisters();
/* Begin Datagram Server Code */
// start gps of dragino gps hat
#ifdef DRAGINO_GPS_HAT
pthread_t read_gps_thread;
int iret;
pthread_mutex_init(&gps_data_mutex,NULL);
iret = pthread_create( &read_gps_thread, NULL, ((void* (*)(void*))&gps_MT3339::read_gps), &gps);
if (iret != 0)
printf("\nCould not start thread to read gps data\n");
#endif
print_scheduler();
/* Begin Datagram Server Code */
while(!flag)
{
if (rf95.available())
{
// Should be a message for us now
uint8_t buf[RH_RF95_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (rf95.recv(buf, &len))
{
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_ON);
#endif
// RF95::printBuffer("request: ", buf, len);
printf("got request: \"%s\"\n", (char*)buf);
printf("RSSI: %d\n",rf95.lastRssi());
uint8_t data[50] = "And hello back to you";
//cut out sequence number from received message (format: "(...)") if in message
// and copy to outgoing message
char* temp1 = strchr((char*)buf,'(');
char* temp2 = strchr((char*)buf,')');
if ((temp1 != NULL) && (temp2 != NULL))
{
// if received message contains sequence number,
// reply with received sequence number
temp1++;
uint8_t wordlen = temp2 - temp1;
temp1[wordlen] = 0x00;
#ifndef DRAGINO_GPS_HAT
snprintf((char*)data+21,8,"(%5s)",temp1);
#else
// In Case of Dragino Lora/GPS hat add timestamp and gps position of server to reply
pthread_mutex_lock(&gps_data_mutex);
snprintf((char*)data,47,"R:(%5s):%10s,%10s,%11s",
temp1,gps.getTimestamp(),gps.getLatitude(),gps.getLongitude());
pthread_mutex_unlock(&gps_data_mutex);
#endif
}
//Send a reply including a trailing 0x00
rf95.send(data, strlen((char*)data)+1);
rf95.waitPacketSent();
printf("Sent a reply: \"%s\"\n",data);
#ifdef RFM95_LED
gpioWrite(RFM95_LED, PI_OFF);
#endif
}
else
{
Serial.println("recv failed");
}
}
}
/* End Datagram Server Code */
printf( "\nrf95_server Tester Ending\n" );
gpioTerminate();
return 0;
}
void sig_handler(int sig)
{
flag=1;
}

View File

@@ -0,0 +1,219 @@
// -*- mode: C++ -*-
/*
* gpsMT3339.cpp
*
* Created on: Jun 11, 2020
* Author: Tilman Glötzner
*/
#include <gpsMT3339.h>
#include <stdio.h>
#include <help_functions.h>
#include <unistd.h>
#include <stdlib.h>
gps_MT3339::gps_MT3339(const char* SerialDevice, pthread_mutex_t* mutex) {
// TODO Auto-generated constructor stub
this->mutex = mutex;
gpsDevice = (char*)malloc(strlen(SerialDevice)*sizeof(char));
if (gpsDevice == NULL)
return;
strcpy(gpsDevice,SerialDevice);
}
gps_MT3339::~gps_MT3339() {
// TODO Auto-generated destructor stub
stop_reading = true;
}
char* gps_MT3339::getLatitude() {
return latitude;
}
char* gps_MT3339::getLongitude() {
return longitude;
}
char* gps_MT3339::getTimestamp() {
return timestamp;
}
//function to read gps device of Dragino GPS hat (to be executed by a thread)
char* gps_MT3339::strnstr(const char *haystack, const char *needle, size_t len)
{
int i;
size_t needle_len;
if (0 == (needle_len = strnlen(needle, len)))
return (char *)haystack;
for (i=0; i<=(int)(len-needle_len); i++)
{
if ((haystack[0] == needle[0]) &&
(0 == strncmp(haystack, needle, needle_len)))
return (char *)haystack;
haystack++;
}
return NULL;
}
void* gps_MT3339::read_gps(void* ptr)
{
ssize_t n, gga_len,i, comma_count;
char* start_ptr;
char* end_ptr;
char gps_buffer[LEN_GPS_READ_BUFFER];
char GPGGA_sentence[LEN_GPS_SENTENCE_BUFFER];
int gps_fd = -1;
int nofchar;
unsigned int empty_read_counter = 0;
printf("\nGPS READER started\n");
print_scheduler();
print_scope();
memset(gps_buffer,0x00,LEN_GPS_READ_BUFFER);
while (!stop_reading)
{
if (gps_fd < 0)
{
// Open the device in non-blocking mode
gps_fd = open(gpsDevice, O_RDWR | O_NONBLOCK);
if(gps_fd < 0)
{
printf("\nWarning: Could not open device file of GPS\n" );
}
}
else
{
n = read(gps_fd, gps_buffer, 200);
if (n == 0)
{
// counter incremented if there was nothing read back
empty_read_counter++;
}
if (n <= 0)
{
if (((errno != EAGAIN) and (errno != EWOULDBLOCK))
|| (empty_read_counter > MAX_EMPTY_READ))
{
// on read error close file descriptor and restart
printf("GPS device being reset\n");
strcpy(longitude,"NoValue");
strcpy(latitude,"NoValue");
strcpy(timestamp,"NoValue");
close(gps_fd);
gps_fd = -1;
empty_read_counter = 0;
memset(gps_buffer,0x00,LEN_GPS_READ_BUFFER);
}
}
else
{
// sucessful read => reset counter tracking empty reads
empty_read_counter = 0;
// Scan for sentence read from GPS device containing position
start_ptr = strnstr (gps_buffer, "$GPGGA", LEN_GPS_READ_BUFFER);
if( start_ptr != NULL)
{
end_ptr = (char*)memchr(start_ptr, '*',
LEN_GPS_READ_BUFFER - (start_ptr - gps_buffer));
if (end_ptr != NULL)
{
gga_len = (end_ptr-start_ptr) < LEN_GPS_SENTENCE_BUFFER ?
(end_ptr-start_ptr) : LEN_GPS_SENTENCE_BUFFER - 1;
memcpy(GPGGA_sentence,gps_buffer,gga_len);
// make sure that string is delimited
GPGGA_sentence[gga_len+1] = '\0';
//printf(GPGGA_sentence);
// extract time and gps coordinates from GPGGA sentence
// Sample: GPGGA,193630.000,4846.8772,N,00912.2288,E,1,5,1.57,131.5,M,48.0,M,,
comma_count = 0;
//printf("%s\n", GPGGA_sentence);
start_ptr = strchr(GPGGA_sentence,',') + 1;
end_ptr=start_ptr;
pthread_mutex_lock(mutex);
while (end_ptr != NULL && start_ptr != NULL)
{
end_ptr = strchr(start_ptr,',');
if (end_ptr != NULL)
{
nofchar = (end_ptr - start_ptr);
if (nofchar < LEN_GPS_INFO_BUFFER)
end_ptr[0] = '\0';
else
break;
int temp = nofchar;
if (comma_count == 0)
{
nofchar = temp < LEN_GPS_INFO_BUFFER ?
temp : LEN_GPS_INFO_BUFFER - 1;
strncpy(timestamp,start_ptr,nofchar);
timestamp[nofchar] = '\0';
}
if (comma_count == 1)
{
nofchar = temp < LEN_GPS_INFO_BUFFER - 2 ?
temp : LEN_GPS_INFO_BUFFER - 2;
strncpy(latitude,start_ptr,nofchar);
latitude[nofchar] = '\0';
}
if (comma_count == 2)
{
nofchar = strlen(latitude);
strncpy(latitude+nofchar,start_ptr,1);
latitude[nofchar+1] = '\0';
}
if (comma_count == 3)
{
nofchar = temp < LEN_GPS_INFO_BUFFER - 2 ?
temp : LEN_GPS_INFO_BUFFER - 2;
strncpy(longitude,start_ptr,nofchar);
longitude[nofchar] = '\0';
}
if (comma_count == 4)
{
nofchar = strlen(longitude);
strncpy(longitude+nofchar,start_ptr,1);
longitude[nofchar+1] = '\0';
// all data extracted => bail out
end_ptr = NULL;
start_ptr = NULL;
}
start_ptr = end_ptr+1;
comma_count++;
}
}
pthread_mutex_unlock(mutex);
}
}
}
}
pthread_yield();
}
free(gpsDevice);
close(gps_fd);
}
void gps_MT3339::stop() {
stop_reading = true;
}

View File

@@ -0,0 +1,52 @@
// -*- mode: C++ -*-
/*
* gpsMT3339.h
*
* Created on: Jun 11, 2020
* Author: Tilman Glötzner
*/
#ifndef GPSMT3339_H_
#define GPSMT3339_H_
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <pthread.h>
#include <errno.h>
#include <string.h>
#define LEN_GPS_READ_BUFFER 255
#define LEN_GPS_INFO_BUFFER 20
#define LEN_GPS_SENTENCE_BUFFER 100
// reading the serial port may eventually lock up.
// MAX_EMPTY_READ determines how many consecutive reads yielding no results, i.e.
// nofCharRead = 0, may occur before the program tries to reopen the gps device
#define MAX_EMPTY_READ 15
#define GPS_DEVICE "/dev/ttyS0"
class gps_MT3339 {
public:
gps_MT3339(const char* SerialDevice,pthread_mutex_t* mutex);
virtual ~gps_MT3339();
void* read_gps(void* ptr);
char* getLatitude();
char* getLongitude();
char* getTimestamp();
void stop();
private:
char *strnstr(const char *haystack, const char *needle, size_t len);
char longitude[LEN_GPS_INFO_BUFFER]="NoInit";
char latitude[LEN_GPS_INFO_BUFFER]="NoInit";
char timestamp[LEN_GPS_INFO_BUFFER]="NoInit";
bool stop_reading = false;
char *gpsDevice;
pthread_mutex_t* mutex;
};
#endif /* GPSMT3339_H_ */

View File

@@ -0,0 +1,56 @@
// -*- mode: C++ -*-
/*
* help_functions.cpp
*
* Created on: Jun 11, 2020
* Author: Tilman Glötzner
*/
// help functions
#include <help_functions.h>
#include <sys/types.h>
#include <unistd.h>
#include <stdio.h>
#include <pthread.h>
void print_scheduler(void)
{
int schedType;
schedType = sched_getscheduler(getpid());
switch(schedType)
{
case SCHED_FIFO:
printf("Scheduling Policy is SCHED_FIFO\n");
break;
case SCHED_OTHER:
printf("Scheduling Policy is SCHED_OTHER\n");
break;
case SCHED_RR:
printf("Scheduling Policy is SCHED_RR\n");
break;
default:
printf("Scheduling Policy is UNKNOWN\n");
}
}
void print_scope(void)
{
pthread_attr_t tattr;
int scope;
int ret;
/* get scope of thread */
ret = pthread_attr_getscope(&tattr, &scope);
switch(scope)
{
case PTHREAD_SCOPE_SYSTEM:
printf("Scheduling Scope is SYSTEM\n");
break;
case PTHREAD_SCOPE_PROCESS:
printf("Scheduling Scope is PROCESS\n");
break;
default:
printf("Scheduling Scope is UNKNOWN\n");
}
}

View File

@@ -0,0 +1,13 @@
// -*- mode: C++ -*-
/*
* help_functions.h
*
* Created on: Jun 11, 2020
* Author: Tilman Glötzner
*/
#ifndef HELP_FUNCTIONS_H_
#define HELP_FUNCTIONS_H_
void print_scheduler(void);
void print_scope(void);
#endif

View File

@@ -0,0 +1,56 @@
// rf22_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple messageing client
// with the RH_RF22 class. RH_RF22 class does not provide for addressing or
// reliability, so you should only use RH_RF22 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example rf22_server
// Tested on Duemilanove, Uno with Sparkfun RFM22 wireless shield
// Tested on Flymaple with sparkfun RFM22 wireless shield
// Tested on ChiKit Uno32 with sparkfun RFM22 wireless shield
#include <SPI.h>
#include <RH_RF22.h>
// Singleton instance of the radio driver
RH_RF22 rf22;
void setup()
{
Serial.begin(9600);
if (!rf22.init())
Serial.println("init failed");
// Defaults after init are 434.0MHz, 0.05MHz AFC pull-in, modulation FSK_Rb2_4Fd36
}
void loop()
{
Serial.println("Sending to rf22_server");
// Send a message to rf22_server
uint8_t data[] = "Hello World!";
rf22.send(data, sizeof(data));
rf22.waitPacketSent();
// Now wait for a reply
uint8_t buf[RH_RF22_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (rf22.waitAvailableTimeout(500))
{
// Should be a reply message for us now
if (rf22.recv(buf, &len))
{
Serial.print("got reply: ");
Serial.println((char*)buf);
}
else
{
Serial.println("recv failed");
}
}
else
{
Serial.println("No reply, is rf22_server running?");
}
delay(400);
}

View File

@@ -0,0 +1,31 @@
// rf22_cw.ino
// -*- mode: C++ -*-
// Example sketch showing how to emit a continuous carrier wave (CW)
// for test purposes
// Tested on Duemilanove, Uno with Sparkfun RFM22 wireless shieldg
#include <SPI.h>
#include <RH_RF22.h>
// Singleton instance of the radio driver
RH_RF22 rf22;
void setup()
{
Serial.begin(9600);
if (!rf22.init())
Serial.println("init failed");
// Defaults after init are 434.0MHz, 0.05MHz AFC pull-in, modulation FSK_Rb2_4Fd36
// CW mode:
rf22.setModemConfig(RH_RF22::UnmodulatedCarrier);
}
void loop()
{
rf22.setModeTx();
delay(1000);
rf22.setModeIdle();
delay(1000);
}

View File

@@ -0,0 +1,68 @@
// rf22_mesh_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, routed reliable messaging client
// with the RHMesh class.
// It is designed to work with the other examples rf22_mesh_server*
// Hint: you can simulate other network topologies by setting the
// RH_TEST_NETWORK define in RHRouter.h
// Mesh has much greater memory requirements, and you may need to limit the
// max message length to prevent wierd crashes
#define RH_MESH_MAX_MESSAGE_LEN 50
#include <RHMesh.h>
#include <RH_RF22.h>
#include <SPI.h>
// In this small artifical network of 4 nodes,
#define CLIENT_ADDRESS 1
#define SERVER1_ADDRESS 2
#define SERVER2_ADDRESS 3
#define SERVER3_ADDRESS 4
// Singleton instance of the radio driver
RH_RF22 driver;
// Class to manage message delivery and receipt, using the driver declared above
RHMesh manager(driver, CLIENT_ADDRESS);
void setup()
{
Serial.begin(9600);
if (!manager.init())
Serial.println("init failed");
// Defaults after init are 434.0MHz, 0.05MHz AFC pull-in, modulation FSK_Rb2_4Fd36
}
uint8_t data[] = "Hello World!";
// Dont put this on the stack:
uint8_t buf[RH_MESH_MAX_MESSAGE_LEN];
void loop()
{
Serial.println("Sending to manager_mesh_server3");
// Send a message to a rf22_mesh_server
// A route to the destination will be automatically discovered.
if (manager.sendtoWait(data, sizeof(data), SERVER3_ADDRESS) == RH_ROUTER_ERROR_NONE)
{
// It has been reliably delivered to the next node.
// Now wait for a reply from the ultimate server
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAckTimeout(buf, &len, 3000, &from))
{
Serial.print("got reply from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
}
else
{
Serial.println("No reply, is rf22_mesh_server1, rf22_mesh_server2 and rf22_mesh_server3 running?");
}
}
else
Serial.println("sendtoWait failed. Are the intermediate mesh servers running?");
}

View File

@@ -0,0 +1,56 @@
// rf22_mesh_server1.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, routed reliable messaging server
// with the RHMesh class.
// It is designed to work with the other examples rf22_mesh_*
// Hint: you can simulate other network topologies by setting the
// RH_TEST_NETWORK define in RHRouter.h
// Mesh has much greater memory requirements, and you may need to limit the
// max message length to prevent wierd crashes
#define RH_MESH_MAX_MESSAGE_LEN 50
#include <RHMesh.h>
#include <RH_RF22.h>
#include <SPI.h>
// In this small artifical network of 4 nodes,
#define CLIENT_ADDRESS 1
#define SERVER1_ADDRESS 2
#define SERVER2_ADDRESS 3
#define SERVER3_ADDRESS 4
// Singleton instance of the radio driver
RH_RF22 driver;
// Class to manage message delivery and receipt, using the driver declared above
RHMesh manager(driver, SERVER1_ADDRESS);
void setup()
{
Serial.begin(9600);
if (!manager.init())
Serial.println("RF22 init failed");
// Defaults after init are 434.0MHz, 0.05MHz AFC pull-in, modulation FSK_Rb2_4Fd36
}
uint8_t data[] = "And hello back to you from server1";
// Dont put this on the stack:
uint8_t buf[RH_MESH_MAX_MESSAGE_LEN];
void loop()
{
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
// Send a reply back to the originator client
if (manager.sendtoWait(data, sizeof(data), from) != RH_ROUTER_ERROR_NONE)
Serial.println("sendtoWait failed");
}
}

View File

@@ -0,0 +1,56 @@
// rf22_mesh_server1.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, routed reliable messaging server
// with the RHMesh class.
// It is designed to work with the other examples rf22_mesh_*
// Hint: you can simulate other network topologies by setting the
// RH_TEST_NETWORK define in RHRouter.h
// Mesh has much greater memory requirements, and you may need to limit the
// max message length to prevent wierd crashes
#define RH_MESH_MAX_MESSAGE_LEN 50
#include <RHMesh.h>
#include <RH_RF22.h>
#include <SPI.h>
// In this small artifical network of 4 nodes,
#define CLIENT_ADDRESS 1
#define SERVER1_ADDRESS 2
#define SERVER2_ADDRESS 3
#define SERVER3_ADDRESS 4
// Singleton instance of the radio driver
RH_RF22 driver;
// Class to manage message delivery and receipt, using the driver declared above
RHMesh manager(driver, SERVER2_ADDRESS);
void setup()
{
Serial.begin(9600);
if (!manager.init())
Serial.println("RF22 init failed");
// Defaults after init are 434.0MHz, 0.05MHz AFC pull-in, modulation FSK_Rb2_4Fd36
}
uint8_t data[] = "And hello back to you from server2";
// Dont put this on the stack:
uint8_t buf[RH_MESH_MAX_MESSAGE_LEN];
void loop()
{
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
// Send a reply back to the originator client
if (manager.sendtoWait(data, sizeof(data), from) != RH_ROUTER_ERROR_NONE)
Serial.println("sendtoWait failed");
}
}

View File

@@ -0,0 +1,56 @@
// rf22_mesh_server3.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, routed reliable messaging server
// with the RHMesh class.
// It is designed to work with the other examples rf22_mesh_*
// Hint: you can simulate other network topologies by setting the
// RH_TEST_NETWORK define in RHRouter.h
// Mesh has much greater memory requirements, and you may need to limit the
// max message length to prevent wierd crashes
#define RH_MESH_MAX_MESSAGE_LEN 50
#include <RHMesh.h>
#include <RH_RF22.h>
#include <SPI.h>
// In this small artifical network of 4 nodes,
#define CLIENT_ADDRESS 1
#define SERVER1_ADDRESS 2
#define SERVER2_ADDRESS 3
#define SERVER3_ADDRESS 4
// Singleton instance of the radio driver
RH_RF22 driver;
// Class to manage message delivery and receipt, using the driver declared above
RHMesh manager(driver, SERVER3_ADDRESS);
void setup()
{
Serial.begin(9600);
if (!manager.init())
Serial.println("RF22 init failed");
// Defaults after init are 434.0MHz, 0.05MHz AFC pull-in, modulation FSK_Rb2_4Fd36
}
uint8_t data[] = "And hello back to you from server3";
// Dont put this on the stack:
uint8_t buf[RH_MESH_MAX_MESSAGE_LEN];
void loop()
{
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
// Send a reply back to the originator client
if (manager.sendtoWait(data, sizeof(data), from) != RH_ROUTER_ERROR_NONE)
Serial.println("sendtoWait failed");
}
}

View File

@@ -0,0 +1,61 @@
// rf22_reliable_datagram_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, reliable messaging client
// with the RHReliableDatagram class, using the RH_RF22 driver to control a RF22 radio.
// It is designed to work with the other example rf22_reliable_datagram_server
// Tested on Duemilanove, Uno with Sparkfun RFM22 wireless shield
// Tested on Flymaple with sparkfun RFM22 wireless shield
// Tested on ChiKit Uno32 with sparkfun RFM22 wireless shield
#include <RHReliableDatagram.h>
#include <RH_RF22.h>
#include <SPI.h>
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
// Singleton instance of the radio driver
RH_RF22 driver;
//RH_RF22 driver(5, 4); // ESP8266
// Class to manage message delivery and receipt, using the driver declared above
RHReliableDatagram manager(driver, CLIENT_ADDRESS);
void setup()
{
Serial.begin(9600);
if (!manager.init())
Serial.println("init failed");
// Defaults after init are 434.0MHz, 0.05MHz AFC pull-in, modulation FSK_Rb2_4Fd36
}
uint8_t data[] = "Hello World!";
// Dont put this on the stack:
uint8_t buf[RH_RF22_MAX_MESSAGE_LEN];
void loop()
{
Serial.println("Sending to rf22_reliable_datagram_server");
// Send a message to manager_server
if (manager.sendtoWait(data, sizeof(data), SERVER_ADDRESS))
{
// Now wait for a reply from the server
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAckTimeout(buf, &len, 2000, &from))
{
Serial.print("got reply from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
}
else
{
Serial.println("No reply, is rf22_reliable_datagram_server running?");
}
}
else
Serial.println("sendtoWait failed");
delay(500);
}

View File

@@ -0,0 +1,56 @@
// rf22_reliable_datagram_server.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, reliable messaging server
// with the RHReliableDatagram class, using the RH_RF22 driver to control a RF22 radio.
// It is designed to work with the other example rf22_reliable_datagram_client
// Tested on Duemilanove, Uno with Sparkfun RFM22 wireless shield
// Tested on Flymaple with sparkfun RFM22 wireless shield
// Tested on ChiKit Uno32 with sparkfun RFM22 wireless shield
#include <RHReliableDatagram.h>
#include <RH_RF22.h>
#include <SPI.h>
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
// Singleton instance of the radio driver
RH_RF22 driver;
//RH_RF22 driver(5, 4); // ESP8266
// Class to manage message delivery and receipt, using the driver declared above
RHReliableDatagram manager(driver, SERVER_ADDRESS);
void setup()
{
Serial.begin(9600);
if (!manager.init())
Serial.println("init failed");
// Defaults after init are 434.0MHz, 0.05MHz AFC pull-in, modulation FSK_Rb2_4Fd36
}
uint8_t data[] = "And hello back to you";
// Dont put this on the stack:
uint8_t buf[RH_RF22_MAX_MESSAGE_LEN];
void loop()
{
if (manager.available())
{
// Wait for a message addressed to us from the client
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
// Send a reply back to the originator client
if (!manager.sendtoWait(data, sizeof(data), from))
Serial.println("sendtoWait failed");
}
}
}

View File

@@ -0,0 +1,72 @@
// rf22_router_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, routed reliable messaging client
// with the RHRouter class.
// It is designed to work with the other examples rf22_router_server*
#include <RHRouter.h>
#include <RH_RF22.h>
#include <SPI.h>
// In this small artifical network of 4 nodes,
// messages are routed via intermediate nodes to their destination
// node. All nodes can act as routers
// CLIENT_ADDRESS <-> SERVER1_ADDRESS <-> SERVER2_ADDRESS<->SERVER3_ADDRESS
#define CLIENT_ADDRESS 1
#define SERVER1_ADDRESS 2
#define SERVER2_ADDRESS 3
#define SERVER3_ADDRESS 4
// Singleton instance of the radio driver
RH_RF22 driver;
// Class to manage message delivery and receipt, using the driver declared above
RHRouter manager(driver, CLIENT_ADDRESS);
void setup()
{
Serial.begin(9600);
if (!manager.init())
Serial.println("init failed");
// Defaults after init are 434.0MHz, 0.05MHz AFC pull-in, modulation FSK_Rb2_4Fd36
// Manually define the routes for this network
manager.addRouteTo(SERVER1_ADDRESS, SERVER1_ADDRESS);
manager.addRouteTo(SERVER2_ADDRESS, SERVER2_ADDRESS);
manager.addRouteTo(SERVER3_ADDRESS, SERVER3_ADDRESS);
}
uint8_t data[] = "Hello World!";
// Dont put this on the stack:
uint8_t buf[RH_ROUTER_MAX_MESSAGE_LEN];
void loop()
{
Serial.println("Sending to rf22_router_server3");
// Send a message to a rf22_router_server
// It will be routed by the intermediate
// nodes to the destination node, accorinding to the
// routing tables in each node
if (manager.sendtoWait(data, sizeof(data), SERVER3_ADDRESS) == RH_ROUTER_ERROR_NONE)
{
// It has been reliably delivered to the next node.
// Now wait for a reply from the ultimate server
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAckTimeout(buf, &len, 3000, &from))
{
Serial.print("got reply from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
}
else
{
Serial.println("No reply, is rf22_router_server1, rf22_router_server2 and rf22_router_server3 running?");
}
}
else
Serial.println("sendtoWait failed. Are the intermediate router servers running?");
}

View File

@@ -0,0 +1,59 @@
// rf22_router_server1.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, routed reliable messaging server
// with the RHRouter class.
// It is designed to work with the other example rf22_router_client
#include <RHRouter.h>
#include <RH_RF22.h>
#include <SPI.h>
// In this small artifical network of 4 nodes,
// messages are routed via intermediate nodes to their destination
// node. All nodes can act as routers
// CLIENT_ADDRESS <-> SERVER1_ADDRESS <-> SERVER2_ADDRESS<->SERVER3_ADDRESS
#define CLIENT_ADDRESS 1
#define SERVER1_ADDRESS 2
#define SERVER2_ADDRESS 3
#define SERVER3_ADDRESS 4
// Singleton instance of the radio
RH_RF22 driver;
// Class to manage message delivery and receipt, using the driver declared above
RHRouter manager(driver, SERVER1_ADDRESS);
void setup()
{
Serial.begin(9600);
if (!manager.init())
Serial.println("init failed");
// Defaults after init are 434.0MHz, 0.05MHz AFC pull-in, modulation FSK_Rb2_4Fd36
// Manually define the routes for this network
manager.addRouteTo(CLIENT_ADDRESS, CLIENT_ADDRESS);
manager.addRouteTo(SERVER2_ADDRESS, SERVER2_ADDRESS);
manager.addRouteTo(SERVER3_ADDRESS, SERVER2_ADDRESS);
}
uint8_t data[] = "And hello back to you from server1";
// Dont put this on the stack:
uint8_t buf[RH_ROUTER_MAX_MESSAGE_LEN];
void loop()
{
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
// Send a reply back to the originator client
if (manager.sendtoWait(data, sizeof(data), from) != RH_ROUTER_ERROR_NONE)
Serial.println("sendtoWait failed");
}
}

View File

@@ -0,0 +1,59 @@
// rf22_router_server2.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, routed reliable messaging server
// with the RHRouter class.
// It is designed to work with the other example rf22_router_client
#include <RHRouter.h>
#include <RH_RF22.h>
#include <SPI.h>
// In this small artifical network of 4 nodes,
// messages are routed via intermediate nodes to their destination
// node. All nodes can act as routers
// CLIENT_ADDRESS <-> SERVER1_ADDRESS <-> SERVER2_ADDRESS<->SERVER3_ADDRESS
#define CLIENT_ADDRESS 1
#define SERVER1_ADDRESS 2
#define SERVER2_ADDRESS 3
#define SERVER3_ADDRESS 4
// Singleton instance of the radio
RH_RF22 driver;
// Class to manage message delivery and receipt, using the driver declared above
RHRouter manager(driver, SERVER2_ADDRESS);
void setup()
{
Serial.begin(9600);
if (!manager.init())
Serial.println("init failed");
// Defaults after init are 434.0MHz, 0.05MHz AFC pull-in, modulation FSK_Rb2_4Fd36
// Manually define the routes for this network
manager.addRouteTo(CLIENT_ADDRESS, CLIENT_ADDRESS);
manager.addRouteTo(SERVER2_ADDRESS, SERVER2_ADDRESS);
manager.addRouteTo(SERVER3_ADDRESS, SERVER2_ADDRESS);
}
uint8_t data[] = "And hello back to you from server2";
// Dont put this on the stack:
uint8_t buf[RH_ROUTER_MAX_MESSAGE_LEN];
void loop()
{
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
// Send a reply back to the originator client
if (manager.sendtoWait(data, sizeof(data), from) != RH_ROUTER_ERROR_NONE)
Serial.println("sendtoWait failed");
}
}

View File

@@ -0,0 +1,59 @@
// rf22_router_server3.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, routed reliable messaging server
// with the RHRouter class.
// It is designed to work with the other example rf22_router_client
#include <RHRouter.h>
#include <RH_RF22.h>
#include <SPI.h>
// In this small artifical network of 4 nodes,
// messages are routed via intermediate nodes to their destination
// node. All nodes can act as routers
// CLIENT_ADDRESS <-> SERVER1_ADDRESS <-> SERVER2_ADDRESS<->SERVER3_ADDRESS
#define CLIENT_ADDRESS 1
#define SERVER1_ADDRESS 2
#define SERVER2_ADDRESS 3
#define SERVER3_ADDRESS 4
// Singleton instance of the radio
RH_RF22 driver;
// Class to manage message delivery and receipt, using the driver declared above
RHRouter manager(driver, SERVER3_ADDRESS);
void setup()
{
Serial.begin(9600);
if (!manager.init())
Serial.println("init failed");
// Defaults after init are 434.0MHz, 0.05MHz AFC pull-in, modulation FSK_Rb2_4Fd36
// Manually define the routes for this network
manager.addRouteTo(CLIENT_ADDRESS, CLIENT_ADDRESS);
manager.addRouteTo(SERVER2_ADDRESS, SERVER2_ADDRESS);
manager.addRouteTo(SERVER3_ADDRESS, SERVER2_ADDRESS);
}
uint8_t data[] = "And hello back to you from server3";
// Dont put this on the stack:
uint8_t buf[RH_ROUTER_MAX_MESSAGE_LEN];
void loop()
{
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
// Send a reply back to the originator client
if (manager.sendtoWait(data, sizeof(data), from) != RH_ROUTER_ERROR_NONE)
Serial.println("sendtoWait failed");
}
}

View File

@@ -0,0 +1,102 @@
// rf22_router_test.pde
// -*- mode: C++ -*-
//
// Test code used during library development, showing how
// to do various things, and how to call various functions
#include <SPI.h>
#include <RHRouter.h>
#include <RH_RF22.h>
#define CLIENT_ADDRESS 1
#define ROUTER_ADDRESS 2
#define SERVER_ADDRESS 3
// Singleton instance of the radio driver
RH_RF22 driver;
// Class to manage message delivery and receipt, using the driver declared above
RHRouter manager(driver, CLIENT_ADDRESS);
void setup()
{
Serial.begin(9600);
if (!manager.init())
Serial.println("RF22 init failed");
// Defaults after init are 434.0MHz, 0.05MHz AFC pull-in, modulation FSK_Rb2_4Fd36
}
void test_routes()
{
manager.clearRoutingTable();
// manager.printRoutingTable();
manager.addRouteTo(1, 101);
manager.addRouteTo(2, 102);
manager.addRouteTo(3, 103);
RHRouter::RoutingTableEntry* e;
e = manager.getRouteTo(0);
if (e) // Should fail
Serial.println("getRouteTo 0 failed");
e = manager.getRouteTo(1);
if (!e)
Serial.println("getRouteTo 1 failed");
if (e->dest != 1)
Serial.println("getRouteTo 2 failed");
if (e->next_hop != 101)
Serial.println("getRouteTo 3 failed");
if (e->state != RHRouter::Valid)
Serial.println("getRouteTo 4 failed");
e = manager.getRouteTo(2);
if (!e)
Serial.println("getRouteTo 5 failed");
if (e->dest != 2)
Serial.println("getRouteTo 6 failed");
if (e->next_hop != 102)
Serial.println("getRouteTo 7 failed");
if (e->state != RHRouter::Valid)
Serial.println("getRouteTo 8 failed");
if (!manager.deleteRouteTo(1))
Serial.println("deleteRouteTo 1 failed");
// Route to 1 should now be gone
e = manager.getRouteTo(1);
if (e)
Serial.println("deleteRouteTo 2 failed");
Serial.println("-------------------");
// manager.printRoutingTable();
delay(500);
}
uint8_t data[] = "Hello World!";
// Dont put this on the stack:
//uint8_t buf[RH_RF22_MAX_MESSAGE_LEN];
void test_tx()
{
manager.addRouteTo(SERVER_ADDRESS, ROUTER_ADDRESS);
uint8_t errorcode;
errorcode = manager.sendtoWait(data, sizeof(data), 100); // Should fail with no route
if (errorcode != RH_ROUTER_ERROR_NO_ROUTE)
Serial.println("sendtoWait 1 failed");
errorcode = manager.sendtoWait(data, 255, 10); // Should fail too big
if (errorcode != RH_ROUTER_ERROR_INVALID_LENGTH)
Serial.println("sendtoWait 2 failed");
errorcode = manager.sendtoWait(data, sizeof(data), SERVER_ADDRESS); // Should fail after timeouts to 110
if (errorcode != RH_ROUTER_ERROR_UNABLE_TO_DELIVER)
Serial.println("sendtoWait 3 failed");
Serial.println("-------------------");
delay(500);
}
void loop()
{
// test_routes();
test_tx();
}

View File

@@ -0,0 +1,53 @@
// rf22_server.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple messageing server
// with the RH_RF22 class. RH_RF22 class does not provide for addressing or
// reliability, so you should only use RH_RF22 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example rf22_client
// Tested on Duemilanove, Uno with Sparkfun RFM22 wireless shield
// Tested on Flymaple with sparkfun RFM22 wireless shield
// Tested on ChiKit Uno32 with sparkfun RFM22 wireless shield
#include <SPI.h>
#include <RH_RF22.h>
// Singleton instance of the radio driver
RH_RF22 rf22;
void setup()
{
Serial.begin(9600);
if (!rf22.init())
Serial.println("init failed");
// Defaults after init are 434.0MHz, 0.05MHz AFC pull-in, modulation FSK_Rb2_4Fd36
}
void loop()
{
if (rf22.available())
{
// Should be a message for us now
uint8_t buf[RH_RF22_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (rf22.recv(buf, &len))
{
// RF22::printBuffer("request: ", buf, len);
Serial.print("got request: ");
Serial.println((char*)buf);
// Serial.print("RSSI: ");
// Serial.println(rf22.lastRssi(), DEC);
// Send a reply
uint8_t data[] = "And hello back to you";
rf22.send(data, sizeof(data));
rf22.waitPacketSent();
Serial.println("Sent a reply");
}
else
{
Serial.println("recv failed");
}
}
}

View File

@@ -0,0 +1,62 @@
// rf24_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple messageing client
// with the RH_RF24 class. RH_RF24 class does not provide for addressing or
// reliability, so you should only use RH_RF24 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example rf24_server.
// Tested on Anarduino Mini http://www.anarduino.com/mini/ with RFM24W and RFM26W
#include <SPI.h>
#include <RH_RF24.h>
// Singleton instance of the radio driver
RH_RF24 rf24;
void setup()
{
Serial.begin(9600);
if (!rf24.init())
Serial.println("init failed");
// The default radio config is for 30MHz Xtal, 434MHz base freq 2GFSK 5kbps 10kHz deviation
// power setting 0x10
// If you want a different frequency mand or modulation scheme, you must generate a new
// radio config file as per the RH_RF24 module documentation and recompile
// You can change a few other things programatically:
//rf24.setFrequency(435.0); // Only within the same frequency band
//rf24.setTxPower(0x7f);
}
void loop()
{
Serial.println("Sending to rf24_server");
// Send a message to rf24_server
uint8_t data[] = "Hello World!";
rf24.send(data, sizeof(data));
rf24.waitPacketSent();
// Now wait for a reply
uint8_t buf[RH_RF24_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (rf24.waitAvailableTimeout(500))
{
// Should be a reply message for us now
if (rf24.recv(buf, &len))
{
Serial.print("got reply: ");
Serial.println((char*)buf);
}
else
{
Serial.println("recv failed");
}
}
else
{
Serial.println("No reply, is rf24_server running?");
}
delay(400);
}

View File

@@ -0,0 +1,80 @@
// rf24_lowpower_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple message transmitter
// which sleeps between transmissions (every 8 secs) to reduce power consumnption
// It uses the watchdog timer and the CPU sleep mode and the radio sleep mode
// to reduce quiescent power to 1.7mA
// Tested on Anarduino Mini http://www.anarduino.com/mini/ with RFM24W and RFM26W
#include <SPI.h>
#include <RH_RF24.h>
#include <avr/sleep.h>
#include <avr/power.h>
// Singleton instance of the radio driver
RH_RF24 rf24;
// Watchdog timer interrupt handler
ISR(WDT_vect)
{
// Dont need to do anything, just override the default vector which causes a reset
}
// Go into sleep mode until WDT interrupt
void sleep()
{
// Select the sleep mode we want. This is the lowest power
// that can wake with WDT interrupt
set_sleep_mode(SLEEP_MODE_PWR_DOWN);
sleep_mode(); // Sleep here and wake on WDT interrupt every 8 secs
}
void setup()
{
Serial.begin(9600);
if (!rf24.init())
Serial.println("init failed");
// The default radio config is for 30MHz Xtal, 434MHz base freq 2GFSK 5kbps 10kHz deviation
// power setting 0x10
// If you want a different frequency mand or modulation scheme, you must generate a new
// radio config file as per the RH_RF24 module documentation and recompile
// You can change a few other things programatically:
//rf24.setFrequency(435.0); // Only within the same frequency band
//rf24.setTxPower(0x7f);
// Set the watchdog timer to interrupt every 8 secs
noInterrupts();
// Set the watchdog reset bit in the MCU status register to 0.
MCUSR &= ~(1<<WDRF);
// Set WDCE and WDE bits in the watchdog control register.
WDTCSR |= (1<<WDCE) | (1<<WDE);
// Set watchdog clock prescaler bits to a value of 8 seconds.
WDTCSR = (1<<WDP0) | (1<<WDP3);
// Enable watchdog as interrupt only (no reset).
WDTCSR |= (1<<WDIE);
// Enable interrupts again.
interrupts();
}
void loop()
{
Serial.println("Sending to rf24_server");
// Send a message to rf24_server
uint8_t data[] = "Hello World!";
rf24.send(data, sizeof(data));
// Make sure its gone before we sleep
rf24.waitPacketSent();
// Anarduino Mini + RFM26, no UART connection (power only)
// 9mA quiescent without any sleep (more during Tx)
// 1.7mA quiescent with radio and CPU sleeping
// radio is 1.58mA while sleeping (in STANDBY state but the antenna switch seems to take some power too)
// 2mA when in Ready state
rf24.sleep();
// Sleep inside here until next WDT in 8 secs
sleep();
}

View File

@@ -0,0 +1,65 @@
// rf24_reliable_datagram_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, reliable messaging client
// with the RHReliableDatagram class, using the RH_RF24 driver to control a RF24 radio.
// It is designed to work with the other example rf24_reliable_datagram_server
// Tested on Anarduino Mini http://www.anarduino.com/mini/ with RFM24W and RFM26W
#include <RHReliableDatagram.h>
#include <RH_RF24.h>
#include <SPI.h>
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
// Singleton instance of the radio driver
RH_RF24 driver;
// Class to manage message delivery and receipt, using the driver declared above
RHReliableDatagram manager(driver, CLIENT_ADDRESS);
void setup()
{
Serial.begin(9600);
if (!manager.init())
Serial.println("init failed");
// The default radio config is for 30MHz Xtal, 434MHz base freq 2GFSK 5kbps 10kHz deviation
// power setting 0x10
// If you want a different frequency mand or modulation scheme, you must generate a new
// radio config file as per the RH_RF24 module documentation and recompile
// You can change a few other things programatically:
//driver.setFrequency(435.0); // Only within the same frequency band
//driver.setTxPower(0x7f);
}
uint8_t data[] = "Hello World!";
// Dont put this on the stack:
uint8_t buf[RH_RF24_MAX_MESSAGE_LEN];
void loop()
{
Serial.println("Sending to rf24_reliable_datagram_server");
// Send a message to manager_server
if (manager.sendtoWait(data, sizeof(data), SERVER_ADDRESS))
{
// Now wait for a reply from the server
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAckTimeout(buf, &len, 2000, &from))
{
Serial.print("got reply from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
}
else
{
Serial.println("No reply, is rf24_reliable_datagram_server running?");
}
}
else
Serial.println("sendtoWait failed");
delay(500);
}

View File

@@ -0,0 +1,59 @@
// rf24_reliable_datagram_server.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, reliable messaging server
// with the RHReliableDatagram class, using the RH_RF24 driver to control a RF24 radio.
// It is designed to work with the other example rf24_reliable_datagram_client
// Tested on Anarduino Mini http://www.anarduino.com/mini/ with RFM24W and RFM26W
#include <RHReliableDatagram.h>
#include <RH_RF24.h>
#include <SPI.h>
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
// Singleton instance of the radio driver
RH_RF24 driver;
// Class to manage message delivery and receipt, using the driver declared above
RHReliableDatagram manager(driver, SERVER_ADDRESS);
void setup()
{
Serial.begin(9600);
if (!manager.init())
Serial.println("init failed");
// The default radio config is for 30MHz Xtal, 434MHz base freq 2GFSK 5kbps 10kHz deviation
// power setting 0x10
// If you want a different frequency mand or modulation scheme, you must generate a new
// radio config file as per the RH_RF24 module documentation and recompile
// You can change a few other things programatically:
//driver.setFrequency(435.0); // Only within the same frequency band
//driver.setTxPower(0x7f);
}
uint8_t data[] = "And hello back to you";
// Dont put this on the stack:
uint8_t buf[RH_RF24_MAX_MESSAGE_LEN];
void loop()
{
if (manager.available())
{
// Wait for a message addressed to us from the client
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
// Send a reply back to the originator client
if (!manager.sendtoWait(data, sizeof(data), from))
Serial.println("sendtoWait failed");
}
}
}

View File

@@ -0,0 +1,57 @@
// rf24_server.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple messageing server
// with the RH_RF24 class. RH_RF24 class does not provide for addressing or
// reliability, so you should only use RH_RF24 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example rf24_client
// Tested on Anarduino Mini http://www.anarduino.com/mini/ with RFM24W and RFM26W
#include <SPI.h>
#include <RH_RF24.h>
// Singleton instance of the radio driver
RH_RF24 rf24;
void setup()
{
Serial.begin(9600);
if (!rf24.init())
Serial.println("init failed");
// The default radio config is for 30MHz Xtal, 434MHz base freq 2GFSK 5kbps 10kHz deviation
// power setting 0x10
// If you want a different frequency mand or modulation scheme, you must generate a new
// radio config file as per the RH_RF24 module documentation and recompile
// You can change a few other things programatically:
//rf24.setFrequency(435.0); // Only within the same frequency band
//rf24.setTxPower(0x7f);
}
void loop()
{
if (rf24.available())
{
// Should be a message for us now
uint8_t buf[RH_RF24_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (rf24.recv(buf, &len))
{
// RF24::printBuffer("request: ", buf, len);
Serial.print("got request: ");
Serial.println((char*)buf);
// Serial.print("RSSI: ");
// Serial.println((uint8_t)rf24.lastRssi(), DEC);
// Send a reply
uint8_t data[] = "And hello back to you";
rf24.send(data, sizeof(data));
rf24.waitPacketSent();
Serial.println("Sent a reply");
}
else
{
Serial.println("recv failed");
}
}
}

View File

@@ -0,0 +1,77 @@
// rf69_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple messageing client
// with the RH_RF69 class. RH_RF69 class does not provide for addressing or
// reliability, so you should only use RH_RF69 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example rf69_server.
// Demonstrates the use of AES encryption, setting the frequency and modem
// configuration
// Tested on Moteino with RFM69 http://lowpowerlab.com/moteino/
// Tested on miniWireless with RFM69 www.anarduino.com/miniwireless
// Tested on Teensy 3.1 with RF69 on PJRC breakout board
#include <SPI.h>
#include <RH_RF69.h>
// Singleton instance of the radio driver
RH_RF69 rf69;
//RH_RF69 rf69(15, 16); // For RF69 on PJRC breakout board with Teensy 3.1
//RH_RF69 rf69(4, 2); // For MoteinoMEGA https://lowpowerlab.com/shop/moteinomega
//RH_RF69 rf69(8, 7); // Adafruit Feather 32u4
void setup()
{
Serial.begin(9600);
while (!Serial)
;
if (!rf69.init())
Serial.println("init failed");
// Defaults after init are 434.0MHz, modulation GFSK_Rb250Fd250, +13dbM (for low power module)
// No encryption
if (!rf69.setFrequency(433.0))
Serial.println("setFrequency failed");
// If you are using a high power RF69 eg RFM69HW, you *must* set a Tx power with the
// ishighpowermodule flag set like this:
//rf69.setTxPower(14, true);
// The encryption key has to be the same as the one in the server
uint8_t key[] = { 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08,
0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08};
rf69.setEncryptionKey(key);
}
void loop()
{
Serial.println("Sending to rf69_server");
// Send a message to rf69_server
uint8_t data[] = "Hello World!";
rf69.send(data, sizeof(data));
rf69.waitPacketSent();
// Now wait for a reply
uint8_t buf[RH_RF69_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (rf69.waitAvailableTimeout(500))
{
// Should be a reply message for us now
if (rf69.recv(buf, &len))
{
Serial.print("got reply: ");
Serial.println((char*)buf);
}
else
{
Serial.println("recv failed");
}
}
else
{
Serial.println("No reply, is rf69_server running?");
}
delay(400);
}

View File

@@ -0,0 +1,70 @@
// rf69_reliable_datagram_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, reliable messaging client
// with the RHReliableDatagram class, using the RH_RF69 driver to control a RF69 radio.
// It is designed to work with the other example rf69_reliable_datagram_server
// Tested on Moteino with RFM69 http://lowpowerlab.com/moteino/
// Tested on miniWireless with RFM69 www.anarduino.com/miniwireless
// Tested on Teensy 3.1 with RF69 on PJRC breakout board
#include <RHReliableDatagram.h>
#include <RH_RF69.h>
#include <SPI.h>
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
// Singleton instance of the radio driver
RH_RF69 driver;
//RH_RF69 driver(15, 16); // For RF69 on PJRC breakout board with Teensy 3.1
//RH_RF69 driver(4, 2); // For MoteinoMEGA https://lowpowerlab.com/shop/moteinomega
//RH_RF69 driver(8, 7); // Adafruit Feather 32u4
// Class to manage message delivery and receipt, using the driver declared above
RHReliableDatagram manager(driver, CLIENT_ADDRESS);
void setup()
{
Serial.begin(9600);
while (!Serial)
;
if (!manager.init())
Serial.println("init failed");
// Defaults after init are 434.0MHz, modulation GFSK_Rb250Fd250, +13dbM (for low power module)
// If you are using a high power RF69 eg RFM69HW, you *must* set a Tx power with the
// ishighpowermodule flag set like this:
//driver.setTxPower(14, true);
}
uint8_t data[] = "Hello World!";
// Dont put this on the stack:
uint8_t buf[RH_RF69_MAX_MESSAGE_LEN];
void loop()
{
Serial.println("Sending to rf69_reliable_datagram_server");
// Send a message to manager_server
if (manager.sendtoWait(data, sizeof(data), SERVER_ADDRESS))
{
// Now wait for a reply from the server
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAckTimeout(buf, &len, 2000, &from))
{
Serial.print("got reply from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
}
else
{
Serial.println("No reply, is rf69_reliable_datagram_server running?");
}
}
else
Serial.println("sendtoWait failed");
delay(500);
}

View File

@@ -0,0 +1,64 @@
// rf69_reliable_datagram_server.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, reliable messaging server
// with the RHReliableDatagram class, using the RH_RF69 driver to control a RF69 radio.
// It is designed to work with the other example rf69_reliable_datagram_client
// Tested on Moteino with RFM69 http://lowpowerlab.com/moteino/
// Tested on miniWireless with RFM69 www.anarduino.com/miniwireless
// Tested on Teensy 3.1 with RF69 on PJRC breakout board
#include <RHReliableDatagram.h>
#include <RH_RF69.h>
#include <SPI.h>
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
// Singleton instance of the radio driver
RH_RF69 driver;
//RH_RF69 driver(15, 16); // For RF69 on PJRC breakout board with Teensy 3.1
//RH_RF69 rf69(4, 2); // For MoteinoMEGA https://lowpowerlab.com/shop/moteinomega
//RH_RF69 driver(8, 7); // Adafruit Feather 32u4
// Class to manage message delivery and receipt, using the driver declared above
RHReliableDatagram manager(driver, SERVER_ADDRESS);
void setup()
{
Serial.begin(9600);
while (!Serial)
;
if (!manager.init())
Serial.println("init failed");
// Defaults after init are 434.0MHz, modulation GFSK_Rb250Fd250, +13dbM (for low power module)
// If you are using a high power RF69 eg RFM69HW, you *must* set a Tx power with the
// ishighpowermodule flag set like this:
//driver.setTxPower(14, true);
}
uint8_t data[] = "And hello back to you";
// Dont put this on the stack:
uint8_t buf[RH_RF69_MAX_MESSAGE_LEN];
void loop()
{
if (manager.available())
{
// Wait for a message addressed to us from the client
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
// Send a reply back to the originator client
if (!manager.sendtoWait(data, sizeof(data), from))
Serial.println("sendtoWait failed");
}
}
}

View File

@@ -0,0 +1,81 @@
// rf69_server.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple messageing server
// with the RH_RF69 class. RH_RF69 class does not provide for addressing or
// reliability, so you should only use RH_RF69 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example rf69_client
// Demonstrates the use of AES encryption, setting the frequency and modem
// configuration.
// Tested on Moteino with RFM69 http://lowpowerlab.com/moteino/
// Tested on miniWireless with RFM69 www.anarduino.com/miniwireless
// Tested on Teensy 3.1 with RF69 on PJRC breakout board
#include <SPI.h>
#include <RH_RF69.h>
// Singleton instance of the radio driver
RH_RF69 rf69;
//RH_RF69 rf69(15, 16); // For RF69 on PJRC breakout board with Teensy 3.1
//RH_RF69 rf69(4, 2); // For MoteinoMEGA https://lowpowerlab.com/shop/moteinomega
//RH_RF69 rf69(8, 7); // Adafruit Feather 32u4
void setup()
{
Serial.begin(9600);
while (!Serial)
;
if (!rf69.init())
Serial.println("init failed");
// Defaults after init are 434.0MHz, modulation GFSK_Rb250Fd250, +13dbM (for low power module)
// No encryption
if (!rf69.setFrequency(433.0))
Serial.println("setFrequency failed");
// If you are using a high power RF69 eg RFM69HW, you *must* set a Tx power with the
// ishighpowermodule flag set like this:
//rf69.setTxPower(14, true);
// The encryption key has to be the same as the one in the client
uint8_t key[] = { 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08,
0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08};
rf69.setEncryptionKey(key);
#if 0
// For compat with RFM69 Struct_send
rf69.setModemConfig(RH_RF69::GFSK_Rb250Fd250);
rf69.setPreambleLength(3);
uint8_t syncwords[] = { 0x2d, 0x64 };
rf69.setSyncWords(syncwords, sizeof(syncwords));
rf69.setEncryptionKey((uint8_t*)"thisIsEncryptKey");
#endif
}
void loop()
{
if (rf69.available())
{
// Should be a message for us now
uint8_t buf[RH_RF69_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (rf69.recv(buf, &len))
{
// RH_RF69::printBuffer("request: ", buf, len);
Serial.print("got request: ");
Serial.println((char*)buf);
// Serial.print("RSSI: ");
// Serial.println(rf69.lastRssi(), DEC);
// Send a reply
uint8_t data[] = "And hello back to you";
rf69.send(data, sizeof(data));
rf69.waitPacketSent();
Serial.println("Sent a reply");
}
else
{
Serial.println("recv failed");
}
}
}

View File

@@ -0,0 +1,83 @@
// rf95_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple messageing client
// with the RH_RF95 class. RH_RF95 class does not provide for addressing or
// reliability, so you should only use RH_RF95 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example rf95_server
// Tested with Anarduino MiniWirelessLoRa, Rocket Scream Mini Ultra Pro with
// the RFM95W, Adafruit Feather M0 with RFM95
#include <SPI.h>
#include <RH_RF95.h>
// Singleton instance of the radio driver
RH_RF95 rf95;
//RH_RF95 rf95(5, 2); // Rocket Scream Mini Ultra Pro with the RFM95W
//RH_RF95 rf95(8, 3); // Adafruit Feather M0 with RFM95
// Need this on Arduino Zero with SerialUSB port (eg RocketScream Mini Ultra Pro)
//#define Serial SerialUSB
void setup()
{
// Rocket Scream Mini Ultra Pro with the RFM95W only:
// Ensure serial flash is not interfering with radio communication on SPI bus
// pinMode(4, OUTPUT);
// digitalWrite(4, HIGH);
Serial.begin(9600);
while (!Serial) ; // Wait for serial port to be available
if (!rf95.init())
Serial.println("init failed");
// Defaults after init are 434.0MHz, 13dBm, Bw = 125 kHz, Cr = 4/5, Sf = 128chips/symbol, CRC on
// You can change the modulation parameters with eg
// rf95.setModemConfig(RH_RF95::Bw500Cr45Sf128);
// The default transmitter power is 13dBm, using PA_BOOST.
// If you are using RFM95/96/97/98 modules which uses the PA_BOOST transmitter pin, then
// you can set transmitter powers from 2 to 20 dBm:
// rf95.setTxPower(20, false);
// If you are using Modtronix inAir4 or inAir9, or any other module which uses the
// transmitter RFO pins and not the PA_BOOST pins
// then you can configure the power transmitter power for 0 to 15 dBm and with useRFO true.
// Failure to do that will result in extremely low transmit powers.
// rf95.setTxPower(14, true);
}
void loop()
{
Serial.println("Sending to rf95_server");
// Send a message to rf95_server
uint8_t data[] = "Hello World!";
rf95.send(data, sizeof(data));
rf95.waitPacketSent();
// Now wait for a reply
uint8_t buf[RH_RF95_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (rf95.waitAvailableTimeout(3000))
{
// Should be a reply message for us now
if (rf95.recv(buf, &len))
{
Serial.print("got reply: ");
Serial.println((char*)buf);
// Serial.print("RSSI: ");
// Serial.println(rf95.lastRssi(), DEC);
}
else
{
Serial.println("recv failed");
}
}
else
{
Serial.println("No reply, is rf95_server running?");
}
delay(400);
}

View File

@@ -0,0 +1,47 @@
// LoRa Simple Hello World Client with encrypted communications
// In order for this to compile you MUST uncomment the #define RH_ENABLE_ENCRYPTION_MODULE line
// at the bottom of RadioHead.h, AND you MUST have installed the Crypto directory from arduinolibs:
// http://rweather.github.io/arduinolibs/index.html
// Philippe.Rochat'at'gmail.com
// 06.07.2017
#include <RH_RF95.h>
#include <RHEncryptedDriver.h>
#include <Speck.h>
RH_RF95 rf95; // Instanciate a LoRa driver
Speck myCipher; // Instanciate a Speck block ciphering
RHEncryptedDriver myDriver(rf95, myCipher); // Instantiate the driver with those two
float frequency = 868.0; // Change the frequency here.
unsigned char encryptkey[16] = {1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16}; // The very secret key
char HWMessage[] = "Hello World ! I'm happy if you can read me";
uint8_t HWMessageLen;
void setup()
{
HWMessageLen = strlen(HWMessage);
Serial.begin(9600);
while (!Serial) ; // Wait for serial port to be available
Serial.println("LoRa Simple_Encrypted Client");
if (!rf95.init())
Serial.println("LoRa init failed");
// Setup ISM frequency
rf95.setFrequency(frequency);
// Setup Power,dBm
rf95.setTxPower(13);
myCipher.setKey(encryptkey, sizeof(encryptkey));
Serial.println("Waiting for radio to setup");
delay(1000);
Serial.println("Setup completed");
}
void loop()
{
uint8_t data[HWMessageLen+1] = {0};
for(uint8_t i = 0; i<= HWMessageLen; i++) data[i] = (uint8_t)HWMessage[i];
myDriver.send(data, sizeof(data)); // Send out ID + Sensor data to LoRa gateway
Serial.print("Sent: ");
Serial.println((char *)&data);
delay(4000);
}

View File

@@ -0,0 +1,48 @@
// LoRa simple server with encrypted communications
// In order for this to compile you MUST uncomment the #define RH_ENABLE_ENCRYPTION_MODULE line
// at the bottom of RadioHead.h, AND you MUST have installed the Crypto directory from arduinolibs:
// http://rweather.github.io/arduinolibs/index.html
// Philippe.Rochat'at'gmail.com
// 06.07.2017
#include <RH_RF95.h>
#include <RHEncryptedDriver.h>
#include <Speck.h>
RH_RF95 rf95; // Instanciate a LoRa driver
Speck myCipher; // Instanciate a Speck block ciphering
RHEncryptedDriver myDriver(rf95, myCipher); // Instantiate the driver with those two
float frequency = 868.0; // Change the frequency here.
unsigned char encryptkey[16]={1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16}; // The very secret key
void setup() {
Serial.begin(9600);
while (!Serial) ; // Wait for serial port to be available
Serial.println("LoRa Simple_Encrypted Server");
if (!rf95.init())
Serial.println("LoRa init failed");
// Setup ISM frequency
rf95.setFrequency(frequency);
// Setup Power,dBm
rf95.setTxPower(13);
myCipher.setKey(encryptkey, 16);
delay(4000);
Serial.println("Setup completed");
}
void loop() {
if (myDriver.available()) {
// Should be a message for us now
uint8_t buf[myDriver.maxMessageLength()];
uint8_t len = sizeof(buf);
if (myDriver.recv(buf, &len)) {
Serial.print("Received: ");
Serial.println((char *)&buf);
}
else
{
Serial.println("recv failed");
}
}
}

View File

@@ -0,0 +1,84 @@
// rf95_reliable_datagram_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, reliable messaging client
// with the RHReliableDatagram class, using the RH_RF95 driver to control a RF95 radio.
// It is designed to work with the other example rf95_reliable_datagram_server
// Tested with Anarduino MiniWirelessLoRa, Rocket Scream Mini Ultra Pro with the RFM95W
#include <RHReliableDatagram.h>
#include <RH_RF95.h>
#include <SPI.h>
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
// Singleton instance of the radio driver
RH_RF95 driver;
//RH_RF95 driver(5, 2); // Rocket Scream Mini Ultra Pro with the RFM95W
// Class to manage message delivery and receipt, using the driver declared above
RHReliableDatagram manager(driver, CLIENT_ADDRESS);
// Need this on Arduino Zero with SerialUSB port (eg RocketScream Mini Ultra Pro)
//#define Serial SerialUSB
void setup()
{
// Rocket Scream Mini Ultra Pro with the RFM95W only:
// Ensure serial flash is not interfering with radio communication on SPI bus
// pinMode(4, OUTPUT);
// digitalWrite(4, HIGH);
Serial.begin(9600);
while (!Serial) ; // Wait for serial port to be available
if (!manager.init())
Serial.println("init failed");
// Defaults after init are 434.0MHz, 13dBm, Bw = 125 kHz, Cr = 4/5, Sf = 128chips/symbol, CRC on
// The default transmitter power is 13dBm, using PA_BOOST.
// If you are using RFM95/96/97/98 modules which uses the PA_BOOST transmitter pin, then
// you can set transmitter powers from 2 to 20 dBm:
// driver.setTxPower(20, false);
// If you are using Modtronix inAir4 or inAir9, or any other module which uses the
// transmitter RFO pins and not the PA_BOOST pins
// then you can configure the power transmitter power for 0 to 15 dBm and with useRFO true.
// Failure to do that will result in extremely low transmit powers.
// driver.setTxPower(14, true);
// You can optionally require this module to wait until Channel Activity
// Detection shows no activity on the channel before transmitting by setting
// the CAD timeout to non-zero:
// driver.setCADTimeout(10000);
}
uint8_t data[] = "Hello World!";
// Dont put this on the stack:
uint8_t buf[RH_RF95_MAX_MESSAGE_LEN];
void loop()
{
Serial.println("Sending to rf95_reliable_datagram_server");
// Send a message to manager_server
if (manager.sendtoWait(data, sizeof(data), SERVER_ADDRESS))
{
// Now wait for a reply from the server
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAckTimeout(buf, &len, 2000, &from))
{
Serial.print("got reply from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
}
else
{
Serial.println("No reply, is rf95_reliable_datagram_server running?");
}
}
else
Serial.println("sendtoWait failed");
delay(500);
}

View File

@@ -0,0 +1,78 @@
// rf95_reliable_datagram_server.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, reliable messaging server
// with the RHReliableDatagram class, using the RH_RF95 driver to control a RF95 radio.
// It is designed to work with the other example rf95_reliable_datagram_client
// Tested with Anarduino MiniWirelessLoRa, Rocket Scream Mini Ultra Pro with the RFM95W
#include <RHReliableDatagram.h>
#include <RH_RF95.h>
#include <SPI.h>
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
// Singleton instance of the radio driver
RH_RF95 driver;
//RH_RF95 driver(5, 2); // Rocket Scream Mini Ultra Pro with the RFM95W
// Class to manage message delivery and receipt, using the driver declared above
RHReliableDatagram manager(driver, SERVER_ADDRESS);
// Need this on Arduino Zero with SerialUSB port (eg RocketScream Mini Ultra Pro)
//#define Serial SerialUSB
void setup()
{
// Rocket Scream Mini Ultra Pro with the RFM95W only:
// Ensure serial flash is not interfering with radio communication on SPI bus
// pinMode(4, OUTPUT);
// digitalWrite(4, HIGH);
Serial.begin(9600);
while (!Serial) ; // Wait for serial port to be available
if (!manager.init())
Serial.println("init failed");
// Defaults after init are 434.0MHz, 13dBm, Bw = 125 kHz, Cr = 4/5, Sf = 128chips/symbol, CRC on
// The default transmitter power is 13dBm, using PA_BOOST.
// If you are using RFM95/96/97/98 modules which uses the PA_BOOST transmitter pin, then
// you can set transmitter powers from 2 to 20 dBm:
// driver.setTxPower(20, false);
// If you are using Modtronix inAir4 or inAir9, or any other module which uses the
// transmitter RFO pins and not the PA_BOOST pins
// then you can configure the power transmitter power for 0 to 15 dBm and with useRFO true.
// Failure to do that will result in extremely low transmit powers.
// driver.setTxPower(14, true);
// You can optionally require this module to wait until Channel Activity
// Detection shows no activity on the channel before transmitting by setting
// the CAD timeout to non-zero:
// driver.setCADTimeout(10000);
}
uint8_t data[] = "And hello back to you";
// Dont put this on the stack:
uint8_t buf[RH_RF95_MAX_MESSAGE_LEN];
void loop()
{
if (manager.available())
{
// Wait for a message addressed to us from the client
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
// Send a reply back to the originator client
if (!manager.sendtoWait(data, sizeof(data), from))
Serial.println("sendtoWait failed");
}
}
}

View File

@@ -0,0 +1,82 @@
// rf95_server.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple messageing server
// with the RH_RF95 class. RH_RF95 class does not provide for addressing or
// reliability, so you should only use RH_RF95 if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example rf95_client
// Tested with Anarduino MiniWirelessLoRa, Rocket Scream Mini Ultra Pro with
// the RFM95W, Adafruit Feather M0 with RFM95
#include <SPI.h>
#include <RH_RF95.h>
// Singleton instance of the radio driver
RH_RF95 rf95;
//RH_RF95 rf95(5, 2); // Rocket Scream Mini Ultra Pro with the RFM95W
//RH_RF95 rf95(8, 3); // Adafruit Feather M0 with RFM95
// Need this on Arduino Zero with SerialUSB port (eg RocketScream Mini Ultra Pro)
//#define Serial SerialUSB
int led = 9;
void setup()
{
// Rocket Scream Mini Ultra Pro with the RFM95W only:
// Ensure serial flash is not interfering with radio communication on SPI bus
// pinMode(4, OUTPUT);
// digitalWrite(4, HIGH);
pinMode(led, OUTPUT);
Serial.begin(9600);
while (!Serial) ; // Wait for serial port to be available
if (!rf95.init())
Serial.println("init failed");
// Defaults after init are 434.0MHz, 13dBm, Bw = 125 kHz, Cr = 4/5, Sf = 128chips/symbol, CRC on
// You can change the modulation parameters with eg
// rf95.setModemConfig(RH_RF95::Bw500Cr45Sf128);
// The default transmitter power is 13dBm, using PA_BOOST.
// If you are using RFM95/96/97/98 modules which uses the PA_BOOST transmitter pin, then
// you can set transmitter powers from 2 to 20 dBm:
// driver.setTxPower(20, false);
// If you are using Modtronix inAir4 or inAir9, or any other module which uses the
// transmitter RFO pins and not the PA_BOOST pins
// then you can configure the power transmitter power for 0 to 15 dBm and with useRFO true.
// Failure to do that will result in extremely low transmit powers.
// driver.setTxPower(14, true);
}
void loop()
{
if (rf95.available())
{
// Should be a message for us now
uint8_t buf[RH_RF95_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (rf95.recv(buf, &len))
{
digitalWrite(led, HIGH);
// RH_RF95::printBuffer("request: ", buf, len);
Serial.print("got request: ");
Serial.println((char*)buf);
// Serial.print("RSSI: ");
// Serial.println(rf95.lastRssi(), DEC);
// Send a reply
uint8_t data[] = "And hello back to you";
rf95.send(data, sizeof(data));
rf95.waitPacketSent();
Serial.println("Sent a reply");
digitalWrite(led, LOW);
}
else
{
Serial.println("recv failed");
}
}
}

View File

@@ -0,0 +1,69 @@
// serial_gateway.pde
// This sketch can be used as a gateway between 2 RadioHead radio networks (connected by a serial line),
// or between
// 1 RadioHead radio network and a Unix host.
// It relays all messages received on the radio driver to the serial port
// (using the RH_Serial driver and protocol). And it relays all messages received on the RH_Serial
// driver port to the radio driver.
// Both drivers operate in promiscuous mode and preserve all headers, so this sketch acts as
// a transparent gateway between RH_Serial and and other RadioHead driver.
//
// By replacing RH_Serial with another RadioHead driver, this can act as a universal gateway
// between any 2 RadioHead networks.
//
// Tested with RF22 driver and RH_Serial driver. The serial port was connected to a Unix host, where the
// serial_reliable_datagram_server.pde was built and running like this:
// tools/simBuild examples/serial/serial_reliable_datagram_server/serial_reliable_datagram_server.pde
// RH_HARDWARESERIAL_DEVICE_NAME=/dev/ttyUSB1 ./serial_reliable_datagram_server
// -*- mode: C++ -*-
//
#include <SPI.h>
#include <RH_RF22.h>
#include <RH_Serial.h>
// Singleton instance of the radio driver
// You can use other radio drivers if you want
RH_RF22 radio;
// Singleton instance of the serial driver which relays all messages
// via Serial to another RadioHead RH_Serial driver, perhaps on a Unix host.
// You could use a different Serial if the arduino has more than 1, eg Serial1 on a Mega
RH_Serial serial(Serial);
void setup()
{
Serial.begin(9600);
if (!radio.init())
Serial.println("radio init failed");
radio.setPromiscuous(true);
// Defaults after init are 434.0MHz, 0.05MHz AFC pull-in, modulation FSK_Rb2_4Fd36
if (!serial.init())
Serial.println("serial init failed");
serial.setPromiscuous(true);
}
uint8_t buf[RH_SERIAL_MAX_MESSAGE_LEN];
void loop()
{
if (radio.available())
{
uint8_t len = sizeof(buf);
radio.recv(buf, &len);
serial.setHeaderTo(radio.headerTo());
serial.setHeaderFrom(radio.headerFrom());
serial.setHeaderId(radio.headerId());
serial.setHeaderFlags(radio.headerFlags(), 0xFF); // Must clear all flags
serial.send(buf, len);
}
if (serial.available())
{
uint8_t len = sizeof(buf);
serial.recv(buf, &len);
radio.setHeaderTo(serial.headerTo());
radio.setHeaderFrom(serial.headerFrom());
radio.setHeaderId(serial.headerId());
radio.setHeaderFlags(serial.headerFlags(), 0xFF); // Must clear all flags
radio.send(buf, len);
}
}

View File

@@ -0,0 +1,83 @@
// serial_reliable_datagram_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, reliable messaging client
// with the RHReliableDatagram class, using the RH_Serial driver to
// communicate using packets over a serial port (or a radio connected to a
// serial port, such as the 3DR Telemetry radio V1 and others).
// It is designed to work with the other example serial_reliable_datagram_server
// Tested on Arduino Mega and ChipKit Uno32 (normal Arduinos only have one
// serial port and so it not possible to test on them and still have debug
// output)
// Tested with Arduino Mega, Teensy 3.1, Moteino, Arduino Due
// Also works on Linux and OSX. Build and test with:
// tools/simBuild examples/serial/serial_reliable_datagram_client/serial_reliable_datagram_client.pde
// RH_HARDWARESERIAL_DEVICE_NAME=/dev/ttyUSB1 ./serial_reliable_datagram_client
#include <RHReliableDatagram.h>
#include <RH_Serial.h>
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
#if (RH_PLATFORM == RH_PLATFORM_UNIX)
#include <RHutil/HardwareSerial.h>
// On Unix we connect to a physical serial port
// You can override this with RH_HARDWARESERIAL_DEVICE_NAME environment variable
HardwareSerial hardwareserial("/dev/ttyUSB0");
RH_Serial driver(hardwareserial);
#else
// On arduino etc, use a predefined local serial port
// eg Serial1 on a Mega
#include <SPI.h>
// Singleton instance of the Serial driver, configured
// to use the port Serial1. Caution: on Uno32, Serial1 is on pins 39 (Rx) and
// 40 (Tx)
RH_Serial driver(Serial1);
#endif
// Class to manage message delivery and receipt, using the driver declared above
RHReliableDatagram manager(driver, CLIENT_ADDRESS);
void setup()
{
Serial.begin(9600);
// Configure the port RH_Serial will use:
driver.serial().begin(9600);
if (!manager.init())
Serial.println("init failed");
//manager.setTimeout(2000); // Might need this at slow data rates or if a radio is involved
}
uint8_t data[] = "Hello World!";
// Dont put this on the stack:
uint8_t buf[RH_SERIAL_MAX_MESSAGE_LEN];
void loop()
{
Serial.println("Sending to serial_reliable_datagram_server");
// Send a message to manager_server
if (manager.sendtoWait(data, sizeof(data), SERVER_ADDRESS))
{
// Now wait for a reply from the server
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAckTimeout(buf, &len, 6000, &from))
{
Serial.print("got reply from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
}
else
{
Serial.println("No reply, is serial_reliable_datagram_server running?");
}
}
else
Serial.println("sendtoWait failed");
delay(500);
}

View File

@@ -0,0 +1,76 @@
// serial_reliable_datagram_server.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, reliable messaging server
// with the RHReliableDatagram class, using the RH_Serial driver to
// communicate using packets over a serial port (or a radio connected to a
// serial port, such as the 3DR Telemetry radio V1 and others).
// It is designed to work with the other example serial_reliable_datagram_client
// Tested on Arduino Mega and ChipKit Uno32 (normal Arduinos only have one
// serial port and so it not possible to test on them and still have debug
// output)
// Tested with Arduino Mega, Teensy 3.1, Moteino, Arduino Due
// Also works on Linux an OSX. Build and test with:
// tools/simBuild examples/serial/serial_reliable_datagram_server/serial_reliable_datagram_server.pde
// RH_HARDWARESERIAL_DEVICE_NAME=/dev/ttyUSB0 ./serial_reliable_datagram_server
#include <RHReliableDatagram.h>
#include <RH_Serial.h>
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
#if (RH_PLATFORM == RH_PLATFORM_UNIX)
#include <RHutil/HardwareSerial.h>
// On Unix we connect to a physical serial port
// You can override this with RH_HARDWARESERIAL_DEVICE_NAME environment variable
HardwareSerial hardwareserial("/dev/ttyUSB0");
RH_Serial driver(hardwareserial);
#else
// On arduino etc, use a predefined local serial port
// eg Serial1 on a Mega
#include <SPI.h>
// Singleton instance of the Serial driver, configured
// to use the port Serial1. Caution: on Uno32, Serial1 is on pins 39 (Rx) and
// 40 (Tx)
RH_Serial driver(Serial1);
#endif
// Class to manage message delivery and receipt, using the driver declared above
RHReliableDatagram manager(driver, SERVER_ADDRESS);
void setup()
{
Serial.begin(9600);
// Configure the port RH_Serial will use:
driver.serial().begin(9600);
if (!manager.init())
Serial.println("init failed");
// manager.setTimeout(2000); // Might need this at slow data rates or if a radio is involved
}
uint8_t data[] = "And hello back to you";
// Dont put this on the stack:
uint8_t buf[RH_SERIAL_MAX_MESSAGE_LEN];
void loop()
{
// Wait for a message addressed to us from the client
manager.waitAvailable();
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
// Send a reply back to the originator client
if (!manager.sendtoWait(data, sizeof(data), from))
Serial.println("sendtoWait failed");
}
}

View File

@@ -0,0 +1,67 @@
// simulator_reliable_datagram_client.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, reliable messaging client
// with the RHReliableDatagram class, using the RH_SIMULATOR driver to control a SIMULATOR radio.
// It is designed to work with the other example simulator_reliable_datagram_server
// Tested on Linux
// Build with
// cd whatever/RadioHead
// tools/simBuild examples/simulator/simulator_reliable_datagram_client/simulator_reliable_datagram_client.pde
// Run with ./simulator_reliable_datagram_client
// Make sure you also have the 'Luminiferous Ether' simulator tools/etherSimulator.pl running
#include <RHReliableDatagram.h>
#include <RH_TCP.h>
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
// Singleton instance of the radio driver
RH_TCP driver;
// Class to manage message delivery and receipt, using the driver declared above
RHReliableDatagram manager(driver, CLIENT_ADDRESS);
void setup()
{
Serial.begin(9600);
if (!manager.init())
Serial.println("init failed");
// Defaults after init are 434.0MHz, 0.05MHz AFC pull-in, modulation FSK_Rb2_4Fd36
// Maybe set this address from teh command line
if (_simulator_argc >= 2)
manager.setThisAddress(atoi(_simulator_argv[1]));
}
uint8_t data[] = "Hello World!";
// Dont put this on the stack:
uint8_t buf[RH_TCP_MAX_MESSAGE_LEN];
void loop()
{
Serial.println("Sending to simulator_reliable_datagram_server");
// Send a message to manager_server
if (manager.sendtoWait(data, sizeof(data), SERVER_ADDRESS))
{
// Now wait for a reply from the server
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAckTimeout(buf, &len, 2000, &from))
{
Serial.print("got reply from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
}
else
{
Serial.println("No reply, is simulator_reliable_datagram_server running?");
}
}
else
Serial.println("sendtoWait failed");
delay(500);
}

View File

@@ -0,0 +1,59 @@
// simulator_reliable_datagram_server.pde
// -*- mode: C++ -*-
// Example sketch showing how to create a simple addressed, reliable messaging server
// with the RHReliableDatagram class, using the RH_SIMULATOR driver to control a SIMULATOR radio.
// It is designed to work with the other example simulator_reliable_datagram_client
// Tested on Linux
// Build with
// cd whatever/RadioHead
// tools/simBuild examples/simulator/simulator_reliable_datagram_server/simulator_reliable_datagram_server.pde
// Run with ./simulator_reliable_datagram_server
// Make sure you also have the 'Luminiferous Ether' simulator tools/etherSimulator.pl running
#include <RHReliableDatagram.h>
#include <RH_TCP.h>
#define CLIENT_ADDRESS 1
#define SERVER_ADDRESS 2
// Singleton instance of the radio driver
RH_TCP driver;
// Class to manage message delivery and receipt, using the driver declared above
RHReliableDatagram manager(driver, SERVER_ADDRESS);
void setup()
{
Serial.begin(9600);
if (!manager.init())
Serial.println("init failed");
// Defaults after init are 434.0MHz, 0.05MHz AFC pull-in, modulation FSK_Rb2_4Fd36
manager.setRetries(0); // Client will ping us if no ack received
// manager.setTimeout(50);
}
uint8_t data[] = "And hello back to you";
// Dont put this on the stack:
uint8_t buf[RH_TCP_MAX_MESSAGE_LEN];
void loop()
{
// Wait for a message addressed to us from the client
manager.waitAvailable();
// Wait for a message addressed to us from the client
uint8_t len = sizeof(buf);
uint8_t from;
if (manager.recvfromAck(buf, &len, &from))
{
Serial.print("got request from : 0x");
Serial.print(from, HEX);
Serial.print(": ");
Serial.println((char*)buf);
// Send a reply back to the originator client
if (!manager.sendtoWait(data, sizeof(data), from))
Serial.println("sendtoWait failed");
}
}

View File

@@ -0,0 +1,74 @@
// stm32wlx_client.ino
// -*- mode: C++ -*-
// Example sketch showing how to create a simple messageing client
// with the STM32WLx class. STM32WLx class does not provide for addressing or
// reliability, so you should only use on its own RH_SX126X if you do not need the higher
// level messaging abilities.
// It is designed to work with the other example stm32wlx_server
// (dont forget to make sure the madulation schemes and frequencies are the same).
// In order to use the Arduino IDE to program the Wio-E5, you must
// install the stm32duino package using these instructions:
// https://community.st.com/t5/stm32-mcus/stm32-arduino-stm32duino-tutorial/ta-p/49649
// Tested with Wio-E5 mini. In Arduino, select:
// Tools -> Board -> STM32 MCU based boards -> LoRa boards
// Tools -> Board part number -> LoRa-E5 mini
// Tools -> U(S)ART support -> Enabled (generic Serial)
#include <SPI.h>
#include <RH_STM32WLx.h>
// Single instance of the driver. The defaults will work for Seed WiO-E5 mini board, and other boards
// equipped with Seeed LoRa-E5 modules, such as NUCLEO_WL55JC1
RH_STM32WLx driver;
void setup()
{
Serial.begin(9600);
while (!Serial) ; // Wait for serial port to be available
if (!driver.init())
Serial.println("init failed");
// Defaults after init are 915.0MHz, 13dBm, Bw = 125 kHz, Cr = 4/5, Sf = 128chips/symbol, CRC on
// You can change the frequency:
// driver.setFrequency(868.0);
// You can change the modulation parameters with eg
// driver.setModemConfig(RH_SX126x::LoRa_Bw125Cr45Sf2048);
// You can change the power level in dBm
// driver.setTxPower(14);
}
void loop()
{
Serial.println("Sending to stm32wlx_server");
// Send a message to stm32wlx_server
uint8_t data[] = "Hello World!";
driver.send(data, sizeof(data));
driver.waitPacketSent();
// Now wait for a reply
uint8_t buf[RH_SX126x_MAX_MESSAGE_LEN];
uint8_t len = sizeof(buf);
if (driver.waitAvailableTimeout(3000))
{
// Should be a reply message for us now
if (driver.recv(buf, &len))
{
Serial.print("got reply: ");
Serial.println((char*)buf);
// Serial.print("RSSI: ");
// Serial.println(driver.lastRssi(), DEC);
}
else
{
Serial.println("recv failed");
}
}
else
{
Serial.println("No reply, is stm32wlx_server running?");
}
delay(400);
}

Some files were not shown because too many files have changed in this diff Show More