Browse Source

Added LoRA

master
Englebert 4 years ago
parent
commit
23e8c65edf
  1. 675
      LoRa_E32.cpp
  2. 298
      LoRa_E32.h
  3. 660
      OpenFlightRX.ino
  4. 20
      README.md
  5. 452
      statesNaming.h

675
LoRa_E32.cpp

@ -0,0 +1,675 @@
#include "LoRa_E32.h"
LoRa_E32::LoRa_E32(HardwareSerial hs) {
this->auxPin = 4;
this->m0Pin = 18;
this->m1Pin = 5;
this->hs = &Serial2;
this->bpsRate = UART_BPS_RATE_9600;
// this->bpsRate = UART_BPS_RATE_115200;
}
bool LoRa_E32::begin(){
pinMode(this->auxPin, INPUT);
pinMode(this->m0Pin, OUTPUT);
pinMode(this->m1Pin, OUTPUT);
digitalWrite(this->m0Pin, HIGH);
digitalWrite(this->m1Pin, HIGH);
if (this->hs){
this->serialDef.begin(*this->hs, this->bpsRate, this->serialConfig);
while (!this->hs) {
}
}
this->serialDef.stream->setTimeout(1000);
Status status = setMode(MODE_0_NORMAL);
return status==SUCCESS;
}
/*
* Utility method to wait until module is doen tranmitting
* a timeout is provided to avoid an infinite loop
*/
Status LoRa_E32::waitCompleteResponse(unsigned long timeout, unsigned int waitNoAux) {
Status result = SUCCESS;
unsigned long t = millis();
// make darn sure millis() is not about to reach max data type limit and start over
if (((unsigned long) (t + timeout)) == 0){
t = 0;
}
// if AUX pin was supplied and look for HIGH state
// note you can omit using AUX if no pins are available, but you will have to use delay() to let module finish
if (this->auxPin != -1) {
while (digitalRead(this->auxPin) == LOW) {
if ((millis() - t) > timeout){
result = ERR_TIMEOUT;
DEBUG_PRINTLN(F("LORA: Timeout error!"));
return result;
}
}
// DEBUG_PRINTLN("AUX HIGH!");
} else {
// if you can't use aux pin, use 4K7 pullup with Arduino
// you may need to adjust this value if transmissions fail
this->managedDelay(waitNoAux);
// DEBUG_PRINTLN(F("Wait no AUX pin!"));
}
// per data sheet control after aux goes high is 2ms so delay for at least that long)
this->managedDelay(20);
// DEBUG_PRINTLN(F("Complete!"));
return result;
}
/*
* delay() in a library is not a good idea as it can stop interrupts
* just poll internal time until timeout is reached
*/
void LoRa_E32::managedDelay(unsigned long timeout) {
unsigned long t = millis();
// make darn sure millis() is not about to reach max data type limit and start over
if(((unsigned long) (t + timeout)) == 0) {
t = 0;
}
while((millis() - t) < timeout) {
}
}
/*
* Method to indicate availability
*/
int LoRa_E32::available(unsigned long timeout) {
// unsigned long t = millis();
//
// // make darn sure millis() is not about to reach max data type limit and start over
// if (((unsigned long) (t + timeout)) == 0){
// t = 0;
// }
//
// if (this->auxPin != 0) {
// if (digitalRead(this->auxPin) == HIGH){
// return 0;
// }else{
// while (digitalRead(this->auxPin) == LOW) {
// if ((millis() - t) > timeout){
// DEBUG_PRINTLN("Timeout error!");
// return 0;
// }
// }
// DEBUG_PRINTLN("AUX HIGH!");
// return 2;
// }
// }else{
return this->serialDef.stream->available();
// }
}
/*
* Method to indicate availability
*/
void LoRa_E32::flush() {
this->serialDef.stream->flush();
}
void LoRa_E32::cleanUARTBuffer() {
// bool IsNull = true;
while (this->available()) {
// IsNull = false;
this->serialDef.stream->read();
}
}
/*
* Method to send a chunk of data provided data is in a struct--my personal favorite as you
* need not parse or worry about sprintf() inability to handle floats
*
* TTP: put your structure definition into a .h file and include in both the sender and reciever
* sketches
*
* NOTE: of your sender and receiver MCU's are different (Teensy and Arduino) caution on the data
* types each handle ints floats differently
*
*/
Status LoRa_E32::sendStruct(void *structureManaged, uint16_t size_) {
if(size_ > MAX_SIZE_TX_PACKET){
return ERR_PACKET_TOO_BIG;
}
Status result = SUCCESS;
uint8_t len = this->serialDef.stream->write((uint8_t *) structureManaged, size_);
if(len!=size_){
DEBUG_PRINT(F("Send... len:"))
DEBUG_PRINT(len);
DEBUG_PRINT(F(" size:"))
DEBUG_PRINT(size_);
if(len==0){
result = ERR_NO_RESPONSE_FROM_DEVICE;
} else {
result = ERR_DATA_SIZE_NOT_MATCH;
}
}
if(result != SUCCESS) return result;
result = this->waitCompleteResponse(1000);
if(result != SUCCESS) return result;
DEBUG_PRINT(F("Clear buffer..."))
this->cleanUARTBuffer();
DEBUG_PRINTLN(F("ok!"))
return result;
}
/*
*
* Method to get a chunk of data provided data is in a struct--my personal favorite as you
* need not parse or worry about sprintf() inability to handle floats
*
* TTP: put your structure definition into a .h file and include in both the sender and reciever
* sketches
*
* NOTE: of your sender and receiver MCU's are different (Teensy and Arduino) caution on the data
* types each handle ints floats differently
*
*/
Status LoRa_E32::receiveStruct(void *structureManaged, uint16_t size_) {
Status result = SUCCESS;
uint8_t len = this->serialDef.stream->readBytes((uint8_t *) structureManaged, size_);
/*
DEBUG_PRINT("Available buffer: ");
DEBUG_PRINT(len);
DEBUG_PRINT(" structure size: ");
DEBUG_PRINTLN(size_);
*/
if(len!=size_){
if(len==0){
result = ERR_NO_RESPONSE_FROM_DEVICE;
} else {
result = ERR_DATA_SIZE_NOT_MATCH;
}
}
if(result != SUCCESS)
return result;
result = this->waitCompleteResponse(1000);
if(result != SUCCESS)
return result;
return result;
}
/*
* method to set the mode (program, normal, etc.)
*/
Status LoRa_E32::setMode(MODE_TYPE mode) {
// data sheet claims module needs some extra time after mode setting (2ms)
// most of my projects uses 10 ms, but 40ms is safer
this->managedDelay(40);
if (this->m0Pin == -1 && this->m1Pin == -1) {
DEBUG_PRINTLN(F("The M0 and M1 pins is not set, this mean that you are connect directly the pins as you need!"))
}else{
switch (mode)
{
case MODE_0_NORMAL:
// Mode 0 | normal operation
digitalWrite(this->m0Pin, LOW);
digitalWrite(this->m1Pin, LOW);
DEBUG_PRINTLN(F("MODE NORMAL!"));
break;
case MODE_1_WAKE_UP:
digitalWrite(this->m0Pin, HIGH);
digitalWrite(this->m1Pin, LOW);
DEBUG_PRINTLN(F("MODE WAKE UP!"));
break;
case MODE_2_POWER_SAVING:
digitalWrite(this->m0Pin, LOW);
digitalWrite(this->m1Pin, HIGH);
DEBUG_PRINTLN(F("MODE POWER SAVING!"));
break;
case MODE_3_SLEEP:
// Mode 3 | Setting operation
digitalWrite(this->m0Pin, HIGH);
digitalWrite(this->m1Pin, HIGH);
DEBUG_PRINTLN(F("MODE PROGRAM/SLEEP!"));
break;
default:
return ERR_INVALID_PARAM;
}
}
// data sheet says 2ms later control is returned, let's give just a bit more time
// these modules can take time to activate pins
this->managedDelay(40);
// wait until aux pin goes back low
Status res = this->waitCompleteResponse(1000);
if(res == SUCCESS){
this->mode = mode;
}
return res;
}
MODE_TYPE LoRa_E32::getMode(){
return this->mode;
}
void LoRa_E32::writeProgramCommand(PROGRAM_COMMAND cmd){
uint8_t CMD[3] = {cmd, cmd, cmd};
uint8_t size = this->serialDef.stream->write(CMD, 3);
DEBUG_PRINTLN(size);
this->managedDelay(50); //need ti check
}
ResponseStructContainer LoRa_E32::getConfiguration(){
ResponseStructContainer rc;
rc.status.code = checkUARTConfiguration(MODE_3_PROGRAM);
if (rc.status.code!=SUCCESS) return rc;
MODE_TYPE prevMode = this->mode;
rc.status.code = this->setMode(MODE_3_PROGRAM);
if (rc.status.code!=SUCCESS) return rc;
this->writeProgramCommand(READ_CONFIGURATION);
rc.data = malloc(sizeof(Configuration));
rc.status.code = this->receiveStruct((uint8_t *)rc.data, sizeof(Configuration));
#ifdef LoRa_E32_DEBUG
this->printParameters((Configuration *)rc.data);
#endif
if (rc.status.code!=SUCCESS) {
this->setMode(prevMode);
return rc;
}
DEBUG_PRINTLN("----------------------------------------");
DEBUG_PRINT(F("HEAD BIN INSIDE: ")); DEBUG_PRINT(((Configuration *)rc.data)->HEAD, BIN);DEBUG_PRINT(" ");DEBUG_PRINT(((Configuration *)rc.data)->HEAD, DEC);DEBUG_PRINT(" ");DEBUG_PRINTLN(((Configuration *)rc.data)->HEAD, HEX);
DEBUG_PRINTLN("----------------------------------------");
rc.status.code = this->setMode(prevMode);
if (rc.status.code!=SUCCESS) return rc;
// this->printParameters(*configuration);
if (0xC0 != ((Configuration *)rc.data)->HEAD && 0xC2 != ((Configuration *)rc.data)->HEAD){
rc.status.code = ERR_HEAD_NOT_RECOGNIZED;
}
// rc.data = configuration;
return rc;
}
RESPONSE_STATUS LoRa_E32::checkUARTConfiguration(MODE_TYPE mode){
if (mode==MODE_3_PROGRAM && this->bpsRate!=UART_BPS_RATE_9600){
return ERR_WRONG_UART_CONFIG;
}
return SUCCESS;
}
ResponseStatus LoRa_E32::setConfiguration(Configuration configuration, PROGRAM_COMMAND saveType){
ResponseStatus rc;
rc.code = checkUARTConfiguration(MODE_3_PROGRAM);
if (rc.code!=SUCCESS) return rc;
MODE_TYPE prevMode = this->mode;
rc.code = this->setMode(MODE_3_PROGRAM);
if (rc.code!=SUCCESS) return rc;
this->writeProgramCommand(READ_CONFIGURATION);
configuration.HEAD = saveType;
rc.code = this->sendStruct((uint8_t *)&configuration, sizeof(Configuration));
if (rc.code!=SUCCESS) {
this->setMode(prevMode);
return rc;
}
DEBUG_PRINTLN("----------------------------------------");
DEBUG_PRINT(F("HEAD BIN INSIDE: ")); DEBUG_PRINT(configuration.HEAD, BIN);DEBUG_PRINT(" ");DEBUG_PRINT(configuration.HEAD, DEC);DEBUG_PRINT(" ");DEBUG_PRINTLN(configuration.HEAD, HEX);
DEBUG_PRINTLN("----------------------------------------");
rc.code = this->setMode(prevMode);
if (rc.code!=SUCCESS) return rc;
// this->printParameters(*configuration);
if (0xC0 != configuration.HEAD && 0xC2 != configuration.HEAD){
rc.code = ERR_HEAD_NOT_RECOGNIZED;
}
return rc;
}
ResponseStructContainer LoRa_E32::getModuleInformation(){
ResponseStructContainer rc;
rc.status.code = checkUARTConfiguration(MODE_3_PROGRAM);
if (rc.status.code!=SUCCESS) return rc;
MODE_TYPE prevMode = this->mode;
rc.status.code = this->setMode(MODE_3_PROGRAM);
if (rc.status.code!=SUCCESS) return rc;
this->writeProgramCommand(READ_MODULE_VERSION);
struct ModuleInformation *moduleInformation = (ModuleInformation *)malloc(sizeof(ModuleInformation));
rc.status.code = this->receiveStruct((uint8_t *)moduleInformation, sizeof(ModuleInformation));
if (rc.status.code!=SUCCESS) {
this->setMode(prevMode);
return rc;
}
rc.status.code = this->setMode(prevMode);
if (rc.status.code!=SUCCESS) return rc;
// this->printParameters(*configuration);
if (0xC3 != moduleInformation->HEAD){
rc.status.code = ERR_HEAD_NOT_RECOGNIZED;
}
DEBUG_PRINTLN("----------------------------------------");
DEBUG_PRINT(F("HEAD BIN INSIDE: ")); DEBUG_PRINT(moduleInformation->HEAD, BIN);DEBUG_PRINT(" ");DEBUG_PRINT(moduleInformation->HEAD, DEC);DEBUG_PRINT(" ");DEBUG_PRINTLN(moduleInformation->HEAD, HEX);
DEBUG_PRINT(F("Freq.: ")); DEBUG_PRINTLN(moduleInformation->frequency, HEX);
DEBUG_PRINT(F("Version : ")); DEBUG_PRINTLN(moduleInformation->version, HEX);
DEBUG_PRINT(F("Features : ")); DEBUG_PRINTLN(moduleInformation->features, HEX);
DEBUG_PRINTLN("----------------------------------------");
rc.data = moduleInformation; // malloc(sizeof (moduleInformation));
return rc;
}
ResponseStatus LoRa_E32::resetModule(){
ResponseStatus status;
status.code = checkUARTConfiguration(MODE_3_PROGRAM);
if (status.code!=SUCCESS) return status;
MODE_TYPE prevMode = this->mode;
status.code = this->setMode(MODE_3_PROGRAM);
if (status.code!=SUCCESS) return status;
this->writeProgramCommand(WRITE_RESET_MODULE);
status.code = this->waitCompleteResponse(1000);
if (status.code!=SUCCESS) {
this->setMode(prevMode);
return status;
}
status.code = this->setMode(prevMode);
if (status.code!=SUCCESS) return status;
return status;
}
ResponseContainer LoRa_E32::receiveMessage(){
ResponseContainer rc;
rc.status.code = SUCCESS;
rc.data = this->serialDef.stream->readString();
this->cleanUARTBuffer();
// if (rc.status.code!=SUCCESS) {
// return rc;
// }
// rc.data = message; // malloc(sizeof (moduleInformation));
return rc;
}
ResponseContainer LoRa_E32::receiveMessageUntil(char delimiter){
ResponseContainer rc;
rc.status.code = SUCCESS;
rc.data = this->serialDef.stream->readStringUntil(delimiter);
// this->cleanUARTBuffer();
// if (rc.status.code!=SUCCESS) {
// return rc;
// }
// rc.data = message; // malloc(sizeof (moduleInformation));
return rc;
}
ResponseStructContainer LoRa_E32::receiveMessage(const uint8_t size){
ResponseStructContainer rc;
rc.data = malloc(size);
rc.status.code = this->receiveStruct((uint8_t *)rc.data, size);
this->cleanUARTBuffer();
if (rc.status.code!=SUCCESS) {
return rc;
}
return rc;
}
ResponseStatus LoRa_E32::sendMessage(const void *message, const uint8_t size){
ResponseStatus status;
status.code = this->sendStruct((uint8_t *)message, size);
if (status.code!=SUCCESS) return status;
return status;
}
ResponseStatus LoRa_E32::sendMessage(const String message){
DEBUG_PRINT(F("Send message: "));
DEBUG_PRINT(message);
byte size = message.length(); // sizeof(message.c_str())+1;
DEBUG_PRINT(F(" size: "));
DEBUG_PRINTLN(size);
char messageFixed[size];
memcpy(messageFixed,message.c_str(),size);
ResponseStatus status;
status.code = this->sendStruct((uint8_t *)&messageFixed, size);
if (status.code!=SUCCESS) return status;
return status;
}
ResponseStatus LoRa_E32::sendFixedMessage(byte ADDH, byte ADDL, byte CHAN, const String message){
// DEBUG_PRINT("String/size: ");
// DEBUG_PRINT(message);
// DEBUG_PRINT("/");
byte size = message.length(); // sizeof(message.c_str())+1;
// DEBUG_PRINTLN(size);
//
// #pragma pack(push, 1)
// struct FixedStransmissionString {
// byte ADDH = 0;
// byte ADDL = 0;
// byte CHAN = 0;
// char message[];
// } fixedStransmission;
// #pragma pack(pop)
//
// fixedStransmission.ADDH = ADDH;
// fixedStransmission.ADDL = ADDL;
// fixedStransmission.CHAN = CHAN;
// char* msg = (char*)message.c_str();
// memcpy(fixedStransmission.message, (char*)msg, size);
//// fixedStransmission.message = message;
//
// DEBUG_PRINT("Message: ");
// DEBUG_PRINTLN(fixedStransmission.message);
//
// ResponseStatus status;
// status.code = this->sendStruct((uint8_t *)&fixedStransmission, sizeof(fixedStransmission));
// if (status.code!=SUCCESS) return status;
//
// return status;
char messageFixed[size];
memcpy(messageFixed,message.c_str(),size);
return this->sendFixedMessage(ADDH, ADDL, CHAN, (uint8_t *)messageFixed, size);
}
ResponseStatus LoRa_E32::sendBroadcastFixedMessage(byte CHAN, const String message){
return this->sendFixedMessage(0xFF, 0xFF, CHAN, message);
}
typedef struct fixedStransmission
{
byte ADDH = 0;
byte ADDL = 0;
byte CHAN = 0;
unsigned char message[];
}FixedStransmission;
FixedStransmission *init_stack(int m){
FixedStransmission *st = (FixedStransmission *)malloc(sizeof(FixedStransmission)+m*sizeof(int));
return st;
}
ResponseStatus LoRa_E32::sendFixedMessage( byte ADDH,byte ADDL, byte CHAN, const void *message, const uint8_t size){
// #pragma pack(push, 1)
// struct FixedStransmission {
// byte ADDH = 0;
// byte ADDL = 0;
// byte CHAN = 0;
// unsigned char message[];
// } fixedStransmission;
// #pragma pack(pop)
FixedStransmission *fixedStransmission = init_stack(size);
// STACK *resize_stack(STACK *st, int m){
// if (m<=st->max){
// return st; /* Take sure do not kill old values */
// }
// STACK *st = (STACK *)realloc(sizeof(STACK)+m*sizeof(int));
// st->max = m;
// return st;
// }
fixedStransmission->ADDH = ADDH;
fixedStransmission->ADDL = ADDL;
fixedStransmission->CHAN = CHAN;
// fixedStransmission.message = &message;
memcpy(fixedStransmission->message,(unsigned char*)message,size);
ResponseStatus status;
status.code = this->sendStruct((uint8_t *)fixedStransmission, size+3);
free(fixedStransmission);
if (status.code!=SUCCESS) return status;
return status;
}
ResponseStatus LoRa_E32::sendBroadcastFixedMessage(byte CHAN, const void *message, const uint8_t size){
return this->sendFixedMessage(0xFF, 0xFF, CHAN, message, size);
}
ResponseContainer LoRa_E32::receiveInitialMessage(uint8_t size){
ResponseContainer rc;
rc.status.code = SUCCESS;
char buff[size];
uint8_t len = this->serialDef.stream->readBytes(buff, size);
if (len!=size) {
if (len==0){
rc.status.code = ERR_NO_RESPONSE_FROM_DEVICE;
}else{
rc.status.code = ERR_DATA_SIZE_NOT_MATCH;
}
return rc;
}
rc.data = buff;
return rc;
}
#define KeeLoq_NLF 0x3A5C742E
unsigned long LoRa_E32::encrypt(unsigned long data)
{
unsigned long x = data;
unsigned long r;
int keyBitNo, index;
unsigned long keyBitVal,bitVal;
for (r = 0; r < 528; r++)
{
keyBitNo = r & 63;
if(keyBitNo < 32)
keyBitVal = bitRead(this->halfKeyloqKey,keyBitNo); // key low
else
keyBitVal = bitRead(this->halfKeyloqKey, keyBitNo - 32);// key hight
index = 1 * bitRead(x,1) + 2 * bitRead(x,9) + 4 * bitRead(x,20) + 8 * bitRead(x,26) + 16 * bitRead(x,31);
bitVal = bitRead(x,0) ^ bitRead(x, 16) ^ bitRead(KeeLoq_NLF,index) ^ keyBitVal;
x = (x>>1) ^ bitVal<<31;
}
return x;
}
unsigned long LoRa_E32::decrypt(unsigned long data)
{
unsigned long x = data;
unsigned long r;
int keyBitNo, index;
unsigned long keyBitVal,bitVal;
for (r = 0; r < 528; r++)
{
keyBitNo = (15-r) & 63;
if(keyBitNo < 32)
keyBitVal = bitRead(this->halfKeyloqKey,keyBitNo); // key low
else
keyBitVal = bitRead(this->halfKeyloqKey, keyBitNo - 32); // key hight
index = 1 * bitRead(x,0) + 2 * bitRead(x,8) + 4 * bitRead(x,19) + 8 * bitRead(x,25) + 16 * bitRead(x,30);
bitVal = bitRead(x,31) ^ bitRead(x, 15) ^ bitRead(KeeLoq_NLF,index) ^ keyBitVal;
x = (x<<1) ^ bitVal;
}
return x;
}
#ifdef LoRa_E32_DEBUG
void LoRa_E32::printParameters(struct Configuration *configuration) {
DEBUG_PRINTLN("----------------------------------------");
DEBUG_PRINT(F("HEAD : ")); DEBUG_PRINT(configuration->HEAD, BIN);DEBUG_PRINT(" ");DEBUG_PRINT(configuration->HEAD, DEC);DEBUG_PRINT(" ");DEBUG_PRINTLN(configuration->HEAD, HEX);
DEBUG_PRINTLN(F(" "));
DEBUG_PRINT(F("AddH : ")); DEBUG_PRINTLN(configuration->ADDH, DEC);
DEBUG_PRINT(F("AddL : ")); DEBUG_PRINTLN(configuration->ADDL, DEC);
DEBUG_PRINT(F("Chan : ")); DEBUG_PRINT(configuration->CHAN, DEC); DEBUG_PRINT(" -> "); DEBUG_PRINTLN(configuration->getChannelDescription());
DEBUG_PRINTLN(F(" "));
DEBUG_PRINT(F("SpeedParityBit : ")); DEBUG_PRINT(configuration->SPED.uartParity, BIN);DEBUG_PRINT(" -> "); DEBUG_PRINTLN(configuration->SPED.getUARTParityDescription());
DEBUG_PRINT(F("SpeedUARTDatte : ")); DEBUG_PRINT(configuration->SPED.uartBaudRate, BIN);DEBUG_PRINT(" -> "); DEBUG_PRINTLN(configuration->SPED.getUARTBaudRate());
DEBUG_PRINT(F("SpeedAirDataRate : ")); DEBUG_PRINT(configuration->SPED.airDataRate, BIN);DEBUG_PRINT(" -> "); DEBUG_PRINTLN(configuration->SPED.getAirDataRate());
DEBUG_PRINT(F("OptionTrans : ")); DEBUG_PRINT(configuration->OPTION.fixedTransmission, BIN);DEBUG_PRINT(" -> "); DEBUG_PRINTLN(configuration->OPTION.getFixedTransmissionDescription());
DEBUG_PRINT(F("OptionPullup : ")); DEBUG_PRINT(configuration->OPTION.ioDriveMode, BIN);DEBUG_PRINT(" -> "); DEBUG_PRINTLN(configuration->OPTION.getIODroveModeDescription());
DEBUG_PRINT(F("OptionWakeup : ")); DEBUG_PRINT(configuration->OPTION.wirelessWakeupTime, BIN);DEBUG_PRINT(" -> "); DEBUG_PRINTLN(configuration->OPTION.getWirelessWakeUPTimeDescription());
DEBUG_PRINT(F("OptionFEC : ")); DEBUG_PRINT(configuration->OPTION.fec, BIN);DEBUG_PRINT(" -> "); DEBUG_PRINTLN(configuration->OPTION.getFECDescription());
DEBUG_PRINT(F("OptionPower : ")); DEBUG_PRINT(configuration->OPTION.transmissionPower, BIN);DEBUG_PRINT(" -> "); DEBUG_PRINTLN(configuration->OPTION.getTransmissionPowerDescription());
DEBUG_PRINTLN("----------------------------------------");
}
#endif

298
LoRa_E32.h

@ -0,0 +1,298 @@
/*
* EBYTE LoRa E32 Series
*/
#ifndef LoRa_E32_h
#define LoRa_E32_h
#ifdef ESP32
#define HARDWARE_SERIAL_SELECTABLE_PIN
#endif
#ifdef ACTIVATE_SOFTWARE_SERIAL
#include <SoftwareSerial.h>
#endif
#include "statesNaming.h"
#if ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h"
#endif
#define MAX_SIZE_TX_PACKET 58
// Uncomment to enable printing out nice debug messages.
// #define LoRa_E32_DEBUG
// Operating Freq
#define FREQUENCY_915
// Define where debug output will be printed.
#define DEBUG_PRINTER Serial
// Setup debug printing macros.
#ifdef LoRa_E32_DEBUG
#define DEBUG_PRINT(...) { DEBUG_PRINTER.print(__VA_ARGS__); }
#define DEBUG_PRINTLN(...) { DEBUG_PRINTER.println(__VA_ARGS__); }
#else
#define DEBUG_PRINT(...) {}
#define DEBUG_PRINTLN(...) {}
#endif
enum MODE_TYPE
{
MODE_0_NORMAL = 0,
MODE_1_WAKE_UP = 1,
MODE_2_POWER_SAVING = 2,
MODE_3_SLEEP = 3,
MODE_3_PROGRAM =3,
MODE_INIT = 0xFF
};
enum PROGRAM_COMMAND
{
WRITE_CFG_PWR_DWN_SAVE = 0xC0,
READ_CONFIGURATION = 0xC1,
WRITE_CFG_PWR_DWN_LOSE = 0xC2,
READ_MODULE_VERSION = 0xC3,
WRITE_RESET_MODULE = 0xC4
};
#pragma pack(push, 1)
struct Speed {
uint8_t airDataRate : 3; //bit 0-2
String getAirDataRate() {
return getAirDataRateDescriptionByParams(this->airDataRate);
}
uint8_t uartBaudRate: 3; //bit 3-5
String getUARTBaudRate() {
return getUARTBaudRateDescriptionByParams(this->uartBaudRate);
}
uint8_t uartParity: 2; //bit 6-7
String getUARTParityDescription() {
return getUARTParityDescriptionByParams(this->uartParity);
}
};
struct Option {
byte transmissionPower : 2; //bit 0-1
String getTransmissionPowerDescription() {
return getTransmissionPowerDescriptionByParams(this->transmissionPower);
}
byte fec : 1; //bit 2
String getFECDescription() {
return getFECDescriptionByParams(this->fec);
}
byte wirelessWakeupTime : 3; //bit 3-5
String getWirelessWakeUPTimeDescription() {
return getWirelessWakeUPTimeDescriptionByParams(this->wirelessWakeupTime);
}
byte ioDriveMode : 1; //bit 6
String getIODroveModeDescription() {
return getIODriveModeDescriptionDescriptionByParams(this->ioDriveMode);
}
byte fixedTransmission : 1; //bit 7
String getFixedTransmissionDescription() {
return getFixedTransmissionDescriptionByParams(this->fixedTransmission);
}
};
struct Configuration {
byte HEAD = 0;
byte ADDH = 0;
byte ADDL = 0;
struct Speed SPED;
byte CHAN = 0;
String getChannelDescription() {
return String(this->CHAN + OPERATING_FREQUENCY) + F("MHz") ;
}
struct Option OPTION;
};
struct ModuleInformation {
byte HEAD = 0;
byte frequency = 0;
byte version = 0;
byte features = 0;
};
struct ResponseStatus {
Status code;
String getResponseDescription() {
return getResponseDescriptionByParams(this->code);
}
};
struct ResponseStructContainer {
void *data;
ResponseStatus status;
void close() {
free(this->data);
}
};
struct ResponseContainer {
String data;
ResponseStatus status;
};
//struct FixedStransmission {
// byte ADDL = 0;
// byte ADDH = 0;
// byte CHAN = 0;
// void *message;
//};
#pragma pack(pop)
class LoRa_E32 {
public:
LoRa_E32(HardwareSerial hs);
/*
#ifdef ACTIVATE_SOFTWARE_SERIAL
LoRa_E32(byte txE32pin, byte rxE32pin, UART_BPS_RATE bpsRate = UART_BPS_RATE_9600);
LoRa_E32(byte txE32pin, byte rxE32pin, byte auxPin, UART_BPS_RATE bpsRate = UART_BPS_RATE_9600);
LoRa_E32(byte txE32pin, byte rxE32pin, byte auxPin, byte m0Pin, byte m1Pin, UART_BPS_RATE bpsRate = UART_BPS_RATE_9600);
#endif
LoRa_E32(HardwareSerial* serial, UART_BPS_RATE bpsRate = UART_BPS_RATE_9600);
LoRa_E32(HardwareSerial* serial, byte auxPin, UART_BPS_RATE bpsRate = UART_BPS_RATE_9600);
LoRa_E32(HardwareSerial* serial, byte auxPin, byte m0Pin, byte m1Pin, UART_BPS_RATE bpsRate = UART_BPS_RATE_9600);
#ifdef HARDWARE_SERIAL_SELECTABLE_PIN
LoRa_E32(byte txE32pin, byte rxE32pin, HardwareSerial* serial, UART_BPS_RATE bpsRate, uint32_t serialConfig = SERIAL_8N1);
LoRa_E32(byte txE32pin, byte rxE32pin, HardwareSerial* serial, byte auxPin, UART_BPS_RATE bpsRate, uint32_t serialConfig = SERIAL_8N1);
LoRa_E32(byte txE32pin, byte rxE32pin, HardwareSerial* serial, byte auxPin, byte m0Pin, byte m1Pin, UART_BPS_RATE bpsRate, uint32_t serialConfig = SERIAL_8N1);
#endif
#ifdef ACTIVATE_SOFTWARE_SERIAL
LoRa_E32(SoftwareSerial* serial, UART_BPS_RATE bpsRate = UART_BPS_RATE_9600);
LoRa_E32(SoftwareSerial* serial, byte auxPin, UART_BPS_RATE bpsRate = UART_BPS_RATE_9600);
LoRa_E32(SoftwareSerial* serial, byte auxPin, byte m0Pin, byte m1Pin, UART_BPS_RATE bpsRate = UART_BPS_RATE_9600);
#endif
// LoRa_E32(byte txE32pin, byte rxE32pin, UART_BPS_RATE bpsRate = UART_BPS_RATE_9600, MODE_TYPE mode = MODE_0_NORMAL);
// LoRa_E32(HardwareSerial* serial = &Serial, UART_BPS_RATE bpsRate = UART_BPS_RATE_9600, MODE_TYPE mode = MODE_0_NORMAL);
// LoRa_E32(SoftwareSerial* serial, UART_BPS_RATE bpsRate = UART_BPS_RATE_9600, MODE_TYPE mode = MODE_0_NORMAL);
*/
bool begin();
Status setMode(MODE_TYPE mode);
MODE_TYPE getMode();
ResponseStructContainer getConfiguration();
ResponseStatus setConfiguration(Configuration configuration, PROGRAM_COMMAND saveType = WRITE_CFG_PWR_DWN_LOSE);
ResponseStructContainer getModuleInformation();
ResponseStatus resetModule();
ResponseStatus sendMessage(const void *message, const uint8_t size);
ResponseStructContainer receiveMessage(const uint8_t size);
ResponseStatus sendMessage(const String message);
ResponseContainer receiveMessage();
ResponseStatus sendFixedMessage(byte ADDH,byte ADDL, byte CHAN, const String message);
ResponseStatus sendBroadcastFixedMessage(byte CHAN, const String message);
ResponseStatus sendFixedMessage(byte ADDH,byte ADDL, byte CHAN, const void *message, const uint8_t size);
ResponseStatus sendBroadcastFixedMessage(byte CHAN, const void *message, const uint8_t size );
ResponseContainer receiveInitialMessage(const uint8_t size);
ResponseContainer receiveMessageUntil(char delimiter = '\0');
int available(unsigned long timeout = 10);
private:
HardwareSerial* hs;
#ifdef ACTIVATE_SOFTWARE_SERIAL
SoftwareSerial* ss;
#endif
bool isSoftwareSerial = true;
int8_t txE32pin = -1;
int8_t rxE32pin = -1;
int8_t auxPin = -1;
#ifdef HARDWARE_SERIAL_SELECTABLE_PIN
uint32_t serialConfig = SERIAL_8N1;
#endif
int8_t m0Pin = -1;
int8_t m1Pin = -1;
unsigned long halfKeyloqKey = 0x06660708;
unsigned long encrypt(unsigned long data);
unsigned long decrypt(unsigned long data);
UART_BPS_RATE bpsRate = UART_BPS_RATE_9600;
struct NeedsStream{
template< typename T >
void begin( T &t, int baud){
DEBUG_PRINTLN("Begin ");
t.setTimeout(500);
t.begin(baud);
stream = &t;
}
#ifdef HARDWARE_SERIAL_SELECTABLE_PIN
// template< typename T >
// void begin( T &t, int baud, SerialConfig config ){
// DEBUG_PRINTLN("Begin ");
// t.setTimeout(500);
// t.begin(baud, config);
// stream = &t;
// }
//
template< typename T >
void begin( T &t, int baud, uint32_t config ){
DEBUG_PRINTLN("Begin ");
t.setTimeout(500);
t.begin(baud, config);
stream = &t;
}
template< typename T >
void begin( T &t, int baud, uint32_t config, int8_t txE32pin, int8_t rxE32pin ){
DEBUG_PRINTLN("Begin ");
t.setTimeout(500);
t.begin(baud, config, txE32pin, rxE32pin);
stream = &t;
}
#endif
void listen(){
}
Stream *stream;
};
NeedsStream serialDef;
MODE_TYPE mode = MODE_0_NORMAL;
void managedDelay(unsigned long timeout);
Status waitCompleteResponse(unsigned long timeout = 1000, unsigned int waitNoAux = 100);
void flush();
void cleanUARTBuffer();
Status sendStruct(void *structureManaged, uint16_t size_);
Status receiveStruct(void *structureManaged, uint16_t size_);
void writeProgramCommand(PROGRAM_COMMAND cmd);
RESPONSE_STATUS checkUARTConfiguration(MODE_TYPE mode);
#ifdef LoRa_E32_DEBUG
void printParameters(struct Configuration *configuration);
#endif
};
#endif

660
OpenFlightRX.ino

@ -1,425 +1,323 @@
/*
* Filename: OpenFlightRX.ino
* Description:
* To receive signals from LoRA module and configurable over WiFi
* DateTime: 2020-10-27
* Author: Englebert
* Date: Fri 25 Sep 2020 04:22:40 PM +08
*
* TODO/Wish Lists:
* 1. BT Serial Relay - For INAV
* 2. WiFi Configuration - NOT going to work because going to cause issue on LoRA speed. Demolish the idea.
* 3. Status Display -
* 4. Sending SBUS over ESP32
* 5. Serial Configuration for the 1st time or debugging
* 6. Configuration over LoRA signals using the last byte.
*
*
* REF:
* WiFi AP - https://randomnerdtutorials.com/esp32-access-point-ap-web-server/
*
* Frequency for RFM95W:
* 900MHz ~ 930MHz (900000000Hz - 930000000Hz)
*
* EEPROM Format:
*
* HFFFFS
*
* H: Header. Must be equal to 0x70. Else this will be consider not valid
* FFFF: 4 bytes Frequency Channel Number
* S: Sync word. Key to prevent other LoRA channels listened. Valid Range: 0x00 ~ 0xFF
* Description:
*
* Signal Format:
* TTYYPPRRS
* TYPRS----
* Hell0 012
* Every power cycle:
* 1. Read configuration from EEPROM
* 2. Set the:
* a. Address: 0x0000 ~ 0xFFFF
* b. Channel: 0x00 ~ 0x1F (900Mhz ~ 931Mhz) (Default at 915Mhz) (Msia: 919 ~ 923)
* c. TXPower: 10dBm, 14dBm, 17dBm, 20dBm
* d. AirRate: 0.3kbps ~ 19.2kbps (Default at 2.4kbps)
*/
#include "Arduino.h"
#include "LoRa_E32.h"
// LoRA Module Needed
#include <SPI.h>
#include <LoRa.h>
// Display
#include <Adafruit_GFX.h>
#include <Adafruit_SSD1306.h>
// For storing configurations and settings
#include <EEPROM.h>
//define the pins used by the transceiver module
#define SS 5
#define RST 14
#define DIO0 2
#define SCREEN_WIDTH 128 // OLED display width, in pixels
#define SCREEN_HEIGHT 64 // OLED display height, in pixels
// Declaration for an SSD1306 display connected to I2C (SDA, SCL pins)
#define OLED_RESET -1 // Reset pin # (or -1 if sharing Arduino reset pin)
Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, OLED_RESET);
uint64_t last_received_lora = 0;
uint64_t last_display = 0;
uint32_t uptime = 0;
uint32_t lora_packets = 0;
uint32_t lora_packets_per_second = 0;
uint32_t delayed = 0;
uint32_t frequency = 900000000;
uint8_t syncword = 0x00;
bool stop_delay = false;
bool tx_mode = false;
bool oled = true;
uint8_t counter = 0;
String LoRaData;
// Example:
// String a = explode("Data|Raw1|Raw2", "|", 4);
String explode(String data, char separator, int index) {
int found = 0;
int strIndex[] = {0, -1};
int maxIndex = data.length() - 1;
for(int i = 0; i <= maxIndex && found<=index; i++) {
if(data.charAt(i) == separator || i == maxIndex) {
found++;
strIndex[0] = strIndex[1]+1;
strIndex[1] = (i == maxIndex) ? i+1 : i;
}
}
return found>index ? data.substring(strIndex[0], strIndex[1]) : "";
}
// Debugging over telnet
#include <WiFi.h>
#define MAX_SRV_CLIENTS 2
const char* ssid = "Pi3_2G";
const char* password = "trustno1";
void showFreeMem() {
Serial.println(F(""));
Serial.print(F("FREE Memory: "));
Serial.println(ESP.getFreeHeap());
}
WiFiServer server(23);
WiFiClient serverClients[MAX_SRV_CLIENTS];
void showHelp() {
Serial.println(F("*** Help ***"));
Serial.print(F("free - Show FREE memory\nhelp - this page\nreboot - restart the device\nsetfreq - change frequency and syncword\ngetfreq - retrive current settings\ntx - TX Mode\nrx - RX Mode\n"));
}
// Temporary hardcode Address...
#define ADDR_H 0x00
#define ADDR_L 0x00
#define CHANNEL 0x13 // 900MHz + 19 = 919MHz (Channel 19)
#define AIR_RATE AIR_DATA_RATE_101_192 // Default to 2.4kbps (AirRate)
#define TX_POWER POWER_17 // Temporary at 17dBm
void resetFunc(void) {
ESP.restart();
}
LoRa_E32 e32ttl100(Serial2);
void getOpenFlightRXSettings(void) {
uint16_t addr = 0x00;
// LoRa related all on Core 0
TaskHandle_t LoraTask;
// If heder not the same then use the default settings
if(EEPROM.read(addr) != 0x70) {
return;
}
// Retriving data
frequency = (EEPROM.read(0x01) << 24) | (EEPROM.read(0x02) << 16) | (EEPROM.read(0x03) << 8) | (EEPROM.read(0x04));
// TTTT TTTT TTTT ---- YYYY YYYY YYYY ---- PPPP PPPP PPPP ---- RRRR RRRR RRRR ---- SSSS SSSS = 72-bits ( 9 bytes )
// Data Structure
struct LoraMessage {
byte throttle[2];
byte yaw[2];
byte pitch[2];
byte roll[2];
byte switches[1];
} lora_message;
/*
Serial.println(frequency);
Serial.println(EEPROM.read(0x01), HEX);
Serial.println(EEPROM.read(0x02), HEX);
Serial.println(EEPROM.read(0x03), HEX);
Serial.println(EEPROM.read(0x04), HEX);
*/
void printParameters(struct Configuration configuration);
void printModuleInformation(struct ModuleInformation moduleInformation);
void setup_lora(void);
void telnet_server(void);
void lora_recv(void);
// Default to minimum if less then 900MHz
if(frequency < 900000000) frequency = 900000000;
int lora_received_count_raw = 0;
int lora_received_count = 0;
// Default to maximum if more than 930MHz
if(frequency > 930000000) frequency = 930000000;
uint32_t last_seconds = 0;
uint32_t last_telnet_seconds = 0;
// Sync Word
syncword = EEPROM.read(0x05);
bool ip_shown = false;
// Receiver or TX mode
tx_mode = EEPROM.read(0x06) & 0x01;
// Debug...
Serial.print(F("Freq:"));
Serial.print(frequency);
Serial.println(F("Hz"));
void setup() {
Serial.begin(115200);
Serial.print(F("Sync:"));
Serial.println(syncword, HEX);
// LoRa Setup
setup_lora();
Serial.print(F("Mode:"));
Serial.println(tx_mode, DEC);
// WiFi Setup
WiFi.begin(ssid, password);
// Telnet
server.begin();
server.setNoDelay(true);
}
void setOpenFlightRXSettings(void) {
uint8_t addr = 0x00;
void loop() {
// Each seconds tick
if(millis() > last_seconds) {
lora_received_count = lora_received_count_raw;
lora_received_count_raw = 0;
last_seconds = millis() + 1000;
// Header
write_data(addr++, 0x70);
Serial.print(F("LoRA:"));
Serial.println(lora_received_count);
// Frequency
write_data(addr++, ((frequency & 0xFF000000) >> 24 ));
Serial.println(EEPROM.read(addr - 1), HEX);
write_data(addr++, ((frequency & 0x00FF0000) >> 16 ));
Serial.println(EEPROM.read(addr - 1), HEX);
write_data(addr++, ((frequency & 0x0000FF00) >> 8));
Serial.println(EEPROM.read(addr - 1), HEX);
write_data(addr++, ((frequency & 0x000000FF)));
Serial.println(EEPROM.read(addr - 1), HEX);
// Sync Word
write_data(addr++, syncword);
Serial.println(EEPROM.read(addr - 1), HEX);
// TX Mode/RX Mode
write_data(addr++, (tx_mode));
Serial.println(EEPROM.read(addr - 1), HEX);
if (WiFi.status() == WL_CONNECTED && ip_shown == false) {
Serial.println(WiFi.localIP());
ip_shown = true;
}
}
Serial.println(F("**** New Settings Saved *****"));
Serial.print(F("FREQ:"));
Serial.println(frequency);
Serial.print(F("SYNC:"));
Serial.println(syncword, HEX);
Serial.print(F("MODE:"));
Serial.println(tx_mode, DEC);
}
lora_recv();
void resetConfig(void) {
// Erase 1st byte will do.
EEPROM.write(0x00, 0x00);
EEPROM.commit();
telnet_server();
}
void write_data(uint16_t addr, uint8_t val) {
// Only enabel the timerAlarmDisable if crash in future....
// timerAlarmDisable(timer);
EEPROM.write(addr, val);
EEPROM.commit();
// timerAlarmEnable(timer);
void lora_recv(void) {
/***** LORA ***/
if(e32ttl100.available() > 1){
ResponseStructContainer rsc = e32ttl100.receiveMessage(sizeof(LoraMessage));
struct LoraMessage loramessage = *(LoraMessage*) rsc.data;
/*
Serial.print(F("Throttle:"));
Serial.println(*(uint16_t*)(loramessage.throttle));
Serial.print(F("Yaw:"));
Serial.println(*(uint16_t*)(loramessage.yaw));
Serial.print(F("Pitch:"));
Serial.println(*(uint16_t*)(loramessage.pitch));
Serial.print(F("Roll:"));
Serial.println(*(uint16_t*)(loramessage.roll));
Serial.print(F("Switches:"));
Serial.println(*(uint8_t*)(loramessage.switches));
// free(rsc.data);
*/
rsc.close();
lora_received_count_raw++;
}
}
/* create a hardware timer */
hw_timer_t * timer = NULL;
void telnet_server(void) {
uint8_t i;
if (WiFi.status() == WL_CONNECTED) {
//check if there are any new clients
if (server.hasClient()){
for(i = 0; i < MAX_SRV_CLIENTS; i++){
//find free/disconnected spot
if (!serverClients[i] || !serverClients[i].connected()){
if(serverClients[i]) serverClients[i].stop();
serverClients[i] = server.available();
if (!serverClients[i]) Serial.println("available broken");
Serial.print("New client: ");
Serial.print(i); Serial.print(' ');
Serial.println(serverClients[i].remoteIP());
break;
}
}
if (i >= MAX_SRV_CLIENTS) {
//no free/disconnected spot so reject
server.available().stop();
}
}
//check clients for data
/*
for(i = 0; i < MAX_SRV_CLIENTS; i++){
if (serverClients[i] && serverClients[i].connected()){
if(serverClients[i].available()){
// get data from the telnet client and push it to the UART
// TODO: CLI STARTS HERE!!!
while(serverClients[i].available()) Serial.write(serverClients[i].read());
}
} else {
if (serverClients[i]) {
serverClients[i].stop();
}
}
}
*/
// TODO.... convert the LoRa...packets to here...so can able to telnet in...
if(millis() > last_telnet_seconds) {
char sbuf[8];
sprintf(sbuf, "RATE:%i\n", lora_received_count);
int len = strlen(sbuf);
for(i = 0; i < MAX_SRV_CLIENTS; i++){
if (serverClients[i] && serverClients[i].connected()){
serverClients[i].write(sbuf, len);
delay(1);
}
}
last_telnet_seconds = millis() + 1000;
}
void IRAM_ATTR onTimer(){
uptime++;
if(!stop_delay) delayed++;
lora_packets_per_second = lora_packets;
lora_packets = 0;
} else {
// Serial.println("WiFi not connected!");
/*
for(i = 0; i < MAX_SRV_CLIENTS; i++) {
if (serverClients[i]) serverClients[i].stop();
}
delay(10);
*/
}
}
void setup() {
//initialize Serial Monitor
Serial.begin(115200);
void setup_lora() {
// Startup all pins and UART
e32ttl100.begin();
while (!Serial);
Serial.println(F("OpenFlightRX v1.0 @ 2020"));
ResponseStructContainer c;
c = e32ttl100.getConfiguration();
// Define a range for the EEPROM (512 bytes). May be can be lesser
EEPROM.begin(512);
// It's important get configuration pointer before all other operation
Configuration configuration = *(Configuration*) c.data;
Serial.println(c.status.getResponseDescription());
Serial.println(c.status.code);
// Getting settings and starts the system
getOpenFlightRXSettings();
printParameters(configuration);
// Setup LoRa transceiver module
LoRa.setPins(SS, RST, DIO0);
/****** Setting up E32 Parameters *****/
// Communication address
configuration.ADDL = ADDR_L;
configuration.ADDH = ADDR_H;
// while (!LoRa.begin(914990000)) {
Serial.print(F("Starting up LoRA"));
while(!LoRa.begin(frequency)) {
Serial.print(F("."));
delay(500);
}
Serial.println(F("OK"));
// The sync word assures you don't get LoRa messages from other LoRa transceivers
// ranges from 0-0xFF
LoRa.setSyncWord(syncword);
LoRa.setPreambleLength(8);
// LoRa.setSpreadingFactor(6);
// LoRa.setSpreadingFactor(7);
//7.8E3, 10.4E3, 15.6E3, 20.8E3, 31.25E3, 41.7E3, 62.5E3, 125E3, and 250E3.
// LoRa.setSignalBandwidth(250E3);
// LoRa.setCodingRate4(5);
// LoRa.setSpreadingFactor(9);
// LoRa.setSignalBandwidth(62.5E3);
// LoRa.setCodingRate4(8);
if(tx_mode)
LoRa.setTxPower(20);
/* Use 1st timer of 4 */
/* 1 tick take 1/(80MHZ/80) = 1us so we set divider 80 and count up */
timer = timerBegin(0, 80, true);
/* Attach onTimer function to our timer */
timerAttachInterrupt(timer, &onTimer, true);
/* Set alarm to call onTimer function every second 1 tick is 1us => 1 second is 1000000us */
/* Repeat the alarm (third parameter) */
timerAlarmWrite(timer, 1000000, true);
/* Start an alarm */
timerAlarmEnable(timer);
/**** TO BE COMMENTED OUT ****/
// SSD1306_SWITCHCAPVCC = generate display voltage from 3.3V internally
if(!display.begin(SSD1306_SWITCHCAPVCC, 0x3C)) {
Serial.println(F("SSD1306 not found"));
oled = false;
}
// Communication channel
configuration.CHAN = CHANNEL;
// Communication rate
configuration.SPED.airDataRate = AIR_RATE;
configuration.SPED.uartBaudRate = UART_BPS_9600;
// configuration.SPED.uartBaudRate = UART_BPS_115200;
configuration.SPED.uartParity = MODE_00_8N1;
// Transmission Power
configuration.OPTION.transmissionPower = TX_POWER;
configuration.OPTION.wirelessWakeupTime = WAKE_UP_1250;
// Other configurations
configuration.OPTION.fec = FEC_0_OFF;
configuration.OPTION.fixedTransmission = FT_FIXED_TRANSMISSION;
configuration.OPTION.ioDriveMode = IO_D_MODE_PUSH_PULLS_PULL_UPS;
// Set not to hold configuration to save the life time of the device ;)
ResponseStatus rs = e32ttl100.setConfiguration(configuration, WRITE_CFG_PWR_DWN_LOSE);
// ResponseStatus rs = e32ttl100.setConfiguration(configuration, WRITE_CFG_PWR_DWN_SAVE);
Serial.println(rs.getResponseDescription());
Serial.println(rs.code);
printParameters(configuration);
if(oled) {
// Clear the buffer
display.clearDisplay();
display.setTextSize(2);
display.setTextColor(SSD1306_WHITE);
display.setCursor(0, 0);
display.print("START RX LORA...");
display.display();
display.clearDisplay();
display.setTextColor(SSD1306_WHITE);
display.setCursor(0, 0);
display.print("DONE!");
display.display();
}
ResponseStructContainer cMi;
cMi = e32ttl100.getModuleInformation();
// It's important get information pointer before all other operation
ModuleInformation mi = *(ModuleInformation*)cMi.data;
Serial.println(cMi.status.getResponseDescription());
Serial.println(cMi.status.code);
printModuleInformation(mi);
c.close();
cMi.close();
// Creating Lora Task on Core 0. This will keep sending over and over again...
// xTaskCreatePinnedToCore(
// RecvLoRaSignals, /* Task function. */
// "RecvLoRaSignals", /* name of task. */
// 10000, /* Stack size of task */
// NULL, /* parameter of the task */
// 0, /* priority of the task */
// &LoraTask, /* Task handle to keep track of created task */
// 0); /* pin task to core 0 */
//
}
void loop() {
if(!tx_mode) {
// try to parse packet
int packetSize = LoRa.parsePacket();
if (packetSize) {
// received a packet
// Serial.print("Received packet '");
if(!stop_delay) {
stop_delay = true;
}
// read packet
while (LoRa.available()) {
LoRaData = LoRa.readString();
// Serial.print(LoRaData);
}
lora_packets++;
last_received_lora = millis();
// print RSSI of packet
// Serial.print("' with RSSI ");
// Serial.println(LoRa.packetRssi());
// if(millis() - last_display > 1000) {
if(oled) {
display.clearDisplay();
display.setTextSize(2);
display.setTextColor(SSD1306_WHITE);
display.setCursor(0, 0);
display.print("RSSI:");
display.print(LoRa.packetRssi());
display.setCursor(0, 16);
display.print("SNR:");
display.print(LoRa.packetSnr());
display.setTextSize(1);
display.setCursor(0, 32);
display.print("Data:");
display.print(LoRaData);
display.setCursor(0, 48);
display.print("Packet/s:");
display.print(lora_packets_per_second);
display.setCursor(0, 40);
display.print("Freq:");
display.print(frequency);
display.setCursor(0, 56);
display.print("Up:");
display.print(uptime);
display.setCursor(64, 56);
display.print("Band: ");
display.print(LoRa.packetFrequencyError());
display.display();
}
/*
Serial.print(F("RSSI:"));
Serial.println(LoRa.packetRssi());
Serial.print(F("SNR:"));
Serial.println(LoRa.packetSnr());
Serial.print(F("Data:"));
Serial.println(LoRaData);
Serial.print(F("Packet/s:"));
Serial.println(lora_packets_per_second);
*/
last_display = millis();
} else {
if(millis() - last_received_lora > 1000) {
if(oled) {
display.clearDisplay();
display.setCursor(0, 0);
display.setTextColor(SSD1306_WHITE);
display.print("SIGNAL LOST");
display.display();
}
}
}
} else {
// TX mode. For distance checking via remote ;)
LoRa.beginPacket();
LoRa.print("HELLO ");
LoRa.print(counter);
LoRa.endPacket();
if(oled) {
display.clearDisplay();
display.setTextSize(2);
display.setTextColor(SSD1306_WHITE);
display.setCursor(0, 0);
display.print("TX MODE");
display.display();
}
counter++;
delay(25);
}
void RecvLoRaSignals(void *pvParameters) {
// Forever loop in this loop :P
for(;;) {
/***** LORA ***/
if(e32ttl100.available() > 1){
ResponseStructContainer rsc = e32ttl100.receiveMessage(sizeof(LoraMessage));
struct LoraMessage loramessage = *(LoraMessage*) rsc.data;
/*
Serial.print(F("Throttle:"));
Serial.println(*(uint16_t*)(loramessage.throttle));
Serial.print(F("Yaw:"));
Serial.println(*(uint16_t*)(loramessage.yaw));
Serial.print(F("Pitch:"));
Serial.println(*(uint16_t*)(loramessage.pitch));
Serial.print(F("Roll:"));
Serial.println(*(uint16_t*)(loramessage.roll));
Serial.print(F("Switches:"));
Serial.println(*(uint8_t*)(loramessage.switches));
// free(rsc.data);
*/
rsc.close();
lora_received_count_raw++;
}
} // End of forever loop - for(;;)
}
void printParameters(struct Configuration configuration) {
Serial.println("----------------------------------------");
Serial.print(F("HEAD BIN: ")); Serial.print(configuration.HEAD, BIN);Serial.print(" ");Serial.print(configuration.HEAD, DEC);Serial.print(" ");Serial.println(configuration.HEAD, HEX);
Serial.println(F(" "));
Serial.print(F("AddH BIN: ")); Serial.println(configuration.ADDH, BIN);
Serial.print(F("AddL BIN: ")); Serial.println(configuration.ADDL, BIN);
Serial.print(F("Chan BIN: ")); Serial.print(configuration.CHAN, DEC); Serial.print(" -> "); Serial.println(configuration.getChannelDescription());
Serial.println(F(" "));
Serial.print(F("SpeedParityBit BIN : ")); Serial.print(configuration.SPED.uartParity, BIN);Serial.print(" -> "); Serial.println(configuration.SPED.getUARTParityDescription());
Serial.print(F("SpeedUARTDataRate BIN : ")); Serial.print(configuration.SPED.uartBaudRate, BIN);Serial.print(" -> "); Serial.println(configuration.SPED.getUARTBaudRate());
Serial.print(F("SpeedAirDataRate BIN : ")); Serial.print(configuration.SPED.airDataRate, BIN);Serial.print(" -> "); Serial.println(configuration.SPED.getAirDataRate());
Serial.print(F("OptionTrans BIN : ")); Serial.print(configuration.OPTION.fixedTransmission, BIN);Serial.print(" -> "); Serial.println(configuration.OPTION.getFixedTransmissionDescription());
Serial.print(F("OptionPullup BIN : ")); Serial.print(configuration.OPTION.ioDriveMode, BIN);Serial.print(" -> "); Serial.println(configuration.OPTION.getIODroveModeDescription());
Serial.print(F("OptionWakeup BIN : ")); Serial.print(configuration.OPTION.wirelessWakeupTime, BIN);Serial.print(" -> "); Serial.println(configuration.OPTION.getWirelessWakeUPTimeDescription());
Serial.print(F("OptionFEC BIN : ")); Serial.print(configuration.OPTION.fec, BIN);Serial.print(" -> "); Serial.println(configuration.OPTION.getFECDescription());
Serial.print(F("OptionPower BIN : ")); Serial.print(configuration.OPTION.transmissionPower, BIN);Serial.print(" -> "); Serial.println(configuration.OPTION.getTransmissionPowerDescription());
Serial.println("----------------------------------------");
// Processing CLI
if(Serial.available() > 0){
String serial_commands_string = Serial.readStringUntil('\n');
serial_commands_string.trim();
String serial_command = explode(serial_commands_string, ' ', 0);
if(serial_command == "reset") {
Serial.println(F("Clearing EEPROM settings..."));
resetConfig();
resetFunc();
} else if(serial_command == "free") {
showFreeMem();
} else if(serial_command == "help") {
showHelp();
} else if(serial_command == "reboot") {
resetFunc();
} else if(serial_command == "setfreq") {
String frequency_raw = explode(serial_commands_string, ' ', 1);
String syncword_raw = explode(serial_commands_string, ' ', 2);
if(
frequency_raw.length() > 0 &&
syncword_raw.length() > 0) {
frequency = frequency_raw.toInt();
syncword = (uint8_t) (syncword_raw.toInt() & 0xFF);
setOpenFlightRXSettings();
}
} else if(serial_command == "getfreq") {
Serial.print(F("FREQ:"));
Serial.println(frequency);
Serial.print(F("SYNC:"));
Serial.println(syncword, HEX);
} else if(serial_command == "tx") {
tx_mode = true;
setOpenFlightRXSettings();
} else if(serial_command == "rx") {
tx_mode = false;
setOpenFlightRXSettings();
}
}
}
void printModuleInformation(struct ModuleInformation moduleInformation) {
Serial.println("----------------------------------------");
Serial.print(F("HEAD BIN: ")); Serial.print(moduleInformation.HEAD, BIN);Serial.print(" ");Serial.print(moduleInformation.HEAD, DEC);Serial.print(" ");Serial.println(moduleInformation.HEAD, HEX);
Serial.print(F("Freq.: ")); Serial.println(moduleInformation.frequency, HEX);
Serial.print(F("Version : ")); Serial.println(moduleInformation.version, HEX);
Serial.print(F("Features : ")); Serial.println(moduleInformation.features, HEX);
Serial.println("----------------------------------------");
}

20
README.md

@ -0,0 +1,20 @@
### Notes:
Every power cycle, E32 settings will reset back to default. Below are the default settings:
SpeedParityBit BIN : 0 -> 8N1 (Default)
SpeedUARTDataRate BIN : 11 -> 9600bps (default)
SpeedAirDataRate BIN : 10 -> 2.4kbps (default)
OptionTrans BIN : 0 -> Transparent transmission (default)
OptionPullup BIN : 1 -> TXD, RXD, AUX are push-pulls/pull-ups
OptionWakeup BIN : 0 -> 250ms (default)
OptionFEC BIN : 1 -> Turn on Forward Error Correction Switch (Default)
OptionPower BIN : 0 -> 20dBm (Default)
Meaning, every startup must load the desire settings into the E32 before starting up. Normal reboot is ok. Only full power cycle will back to default.
Things to be configure before power on:
Transmission Power: 10, 14, 17 and 20
Address: 0x0000 ~ 0xFFFE
Channel: 900MHz ~ 931MHz
TXPower: 19.3dBm ~ 20.0dBm
AirRate: 0.3kbps ~ 19.2kbps (2.4kbps) <--- Testing on 2.4 first. Based on calculation is about 300 Bytes/second.

452
statesNaming.h

@ -0,0 +1,452 @@
#include "Arduino.h"
#define FREQUENCY_915
#ifdef FREQUENCY_433
#define OPERATING_FREQUENCY 410
#elif defined(FREQUENCY_170)
#define OPERATING_FREQUENCY 130
#elif defined(FREQUENCY_470)
#define OPERATING_FREQUENCY 370
#elif defined(FREQUENCY_868)
#define OPERATING_FREQUENCY 862
#elif defined(FREQUENCY_915)
#define OPERATING_FREQUENCY 900
#else
#define OPERATING_FREQUENCY 410
#endif
#define BROADCAST_ADDRESS 0xFF
typedef enum RESPONSE_STATUS {
SUCCESS = 1,
ERR_UNKNOWN, /* something shouldn't happened */
ERR_NOT_SUPPORT,
ERR_NOT_IMPLEMENT,
ERR_NOT_INITIAL,
ERR_INVALID_PARAM,
ERR_DATA_SIZE_NOT_MATCH,
ERR_BUF_TOO_SMALL,
ERR_TIMEOUT,
ERR_HARDWARE,
ERR_HEAD_NOT_RECOGNIZED,
ERR_NO_RESPONSE_FROM_DEVICE,
ERR_WRONG_UART_CONFIG,
ERR_PACKET_TOO_BIG
} Status;
static String getResponseDescriptionByParams(byte status){
switch (status)
{
case SUCCESS:
return F("Success");
break;
case ERR_UNKNOWN:
return F("Unknown");
break;
case ERR_NOT_SUPPORT:
return F("Not support!");
break;
case ERR_NOT_IMPLEMENT:
return F("Not implement");
break;
case ERR_NOT_INITIAL:
return F("Not initial!");
break;
case ERR_INVALID_PARAM:
return F("Invalid param!");
break;
case ERR_DATA_SIZE_NOT_MATCH:
return F("Data size not match!");
break;
case ERR_BUF_TOO_SMALL:
return F("Buff too small!");
break;
case ERR_TIMEOUT:
return F("Timeout!!");
break;
case ERR_HARDWARE:
return F("Hardware error!");
break;
case ERR_HEAD_NOT_RECOGNIZED:
return F("Save mode returned not recognized!");
break;
case ERR_NO_RESPONSE_FROM_DEVICE:
return F("No response from device! (Check wiring)");
break;
case ERR_WRONG_UART_CONFIG:
return F("Wrong UART configuration! (BPS must be 9600 for configuration)");
break;
case ERR_PACKET_TOO_BIG:
return F("The device support only 58byte of data transmission!");
break;
default:
return F("Invalid status!");
}
}
enum UART_PARITY
{
MODE_00_8N1 = B00,
MODE_01_8O1 = B01,
MODE_10_8E1 = B10,
MODE_11_8N1 = B11
};
static String getUARTParityDescriptionByParams(byte uartParity){
switch (uartParity)
{
case MODE_00_8N1:
return F("8N1 (Default)");
break;
case MODE_01_8O1:
return F("8O1");
break;
case MODE_10_8E1:
return F("8E1");
break;
case MODE_11_8N1:
return F("8N1");
break;
default:
return F("Invalid UART Parity!");
}
}
enum UART_BPS_TYPE
{
UART_BPS_1200 = B000,
UART_BPS_2400 = B001,
UART_BPS_4800 = B010,
UART_BPS_9600 = B011,
UART_BPS_19200 = B100,
UART_BPS_38400 = B101,
UART_BPS_57600 = B110,
UART_BPS_115200 = B111
};
enum UART_BPS_RATE
{
UART_BPS_RATE_1200 = 1200,
UART_BPS_RATE_2400 = 2400,
UART_BPS_RATE_4800 = 4800,
UART_BPS_RATE_9600 = 9600,
UART_BPS_RATE_19200 = 19200,
UART_BPS_RATE_38400 = 38400,
UART_BPS_RATE_57600 = 57600,
UART_BPS_RATE_115200 = 115200
};
static String getUARTBaudRateDescriptionByParams(byte uartBaudRate)
{
switch (uartBaudRate)
{
case UART_BPS_1200:
return F("1200bps");
break;
case UART_BPS_2400:
return F("2400bps");
break;
case UART_BPS_4800:
return F("4800bps");
break;
case UART_BPS_9600:
return F("9600bps (default)");
break;
case UART_BPS_19200:
return F("19200bps");
break;
case UART_BPS_38400:
return F("38400bps");
break;
case UART_BPS_57600:
return F("57600bps");
break;
case UART_BPS_115200:
return F("115200bps");
break;
default:
return F("Invalid UART Baud Rate!");
}
}
enum AIR_DATA_RATE
{
AIR_DATA_RATE_000_03 = B000,
AIR_DATA_RATE_001_12 = B001,
AIR_DATA_RATE_010_24 = B010,
AIR_DATA_RATE_011_48 = B011,
AIR_DATA_RATE_100_96 = B100,
AIR_DATA_RATE_101_192 = B101,
AIR_DATA_RATE_110_192 = B110,
AIR_DATA_RATE_111_192 = B111
};
static String getAirDataRateDescriptionByParams(byte airDataRate)
{
switch (airDataRate)
{
case AIR_DATA_RATE_000_03:
return F("0.3kbps");
break;
case AIR_DATA_RATE_001_12:
return F("1.2kbps");
break;
case AIR_DATA_RATE_010_24:
return F("2.4kbps (default)");
break;
case AIR_DATA_RATE_011_48:
return F("4.8kbps");
break;
case AIR_DATA_RATE_100_96:
return F("9.6kbps");
break;
case AIR_DATA_RATE_101_192:
return F("19.2kbps");
break;
case AIR_DATA_RATE_110_192:
return F("19.2kbps");
break;
case AIR_DATA_RATE_111_192:
return F("19.2kbps");
break;
default:
return F("Invalid Air Data Rate!");
}
}
enum FIDEX_TRANSMISSION
{
FT_TRANSPARENT_TRANSMISSION = B0,
FT_FIXED_TRANSMISSION = B1
};
static String getFixedTransmissionDescriptionByParams(byte fixedTransmission)
{
switch (fixedTransmission)
{
case FT_TRANSPARENT_TRANSMISSION:
return F("Transparent transmission (default)");
break;
case FT_FIXED_TRANSMISSION:
return F("Fixed transmission (first three bytes can be used as high/low address and channel)");
break;
default:
return F("Invalid fixed transmission param!");
}
}
enum IO_DRIVE_MODE
{
IO_D_MODE_OPEN_COLLECTOR = B0,
IO_D_MODE_PUSH_PULLS_PULL_UPS = B1
};
static String getIODriveModeDescriptionDescriptionByParams(byte ioDriveMode)
{
switch (ioDriveMode)
{
case IO_D_MODE_OPEN_COLLECTOR:
return F("TXD, RXD, AUX are open-collectors");
break;
case IO_D_MODE_PUSH_PULLS_PULL_UPS:
return F("TXD, RXD, AUX are push-pulls/pull-ups");
break;
default:
return F("Invalid IO drive mode!");
}
}
enum WIRELESS_WAKE_UP_TIME
{
WAKE_UP_250 = B000,
WAKE_UP_500 = B001,
WAKE_UP_750 = B010,
WAKE_UP_1000 = B011,
WAKE_UP_1250 = B100,
WAKE_UP_1500 = B101,
WAKE_UP_1750 = B110,
WAKE_UP_2000 = B111
};
static String getWirelessWakeUPTimeDescriptionByParams(byte wirelessWakeUPTime)
{
switch (wirelessWakeUPTime)
{
case WAKE_UP_250:
return F("250ms (default)");
break;
case WAKE_UP_500:
return F("500ms");
break;
case WAKE_UP_750:
return F("750ms");
break;
case WAKE_UP_1000:
return F("1000ms");
break;
case WAKE_UP_1250:
return F("1250ms");
break;
case WAKE_UP_1500:
return F("1500ms");
break;
case WAKE_UP_1750:
return F("1750ms");
break;
case WAKE_UP_2000:
return F("2000ms");
break;
default:
return F("Invalid wireless wake-up mode!");
}
}
enum FORWARD_ERROR_CORRECTION_SWITCH
{
FEC_0_OFF = B0,
FEC_1_ON = B1
};
static String getFECDescriptionByParams(byte fec)
{
switch (fec)
{
case FEC_0_OFF:
return F("Turn off Forward Error Correction Switch");
break;
case FEC_1_ON:
return F("Turn on Forward Error Correction Switch (Default)");
break;
default:
return F("Invalid FEC param");
}
}
#ifdef E32_TTL_100
enum TRANSMISSION_POWER
{
POWER_20 = B00,
POWER_17 = B01,
POWER_14 = B10,
POWER_10 = B11
};
static String getTransmissionPowerDescriptionByParams(byte transmissionPower)
{
switch (transmissionPower)
{
case POWER_20:
return F("20dBm (Default)");
break;
case POWER_17:
return F("17dBm");
break;
case POWER_14:
return F("14dBm");
break;
case POWER_10:
return F("10dBm");
break;
default:
return F("Invalid transmission power param");
}
}
#elif defined(E32_TTL_500)
enum TRANSMISSION_POWER
{
POWER_27 = B00,
POWER_24 = B01,
POWER_21 = B10,
POWER_18 = B11
};
static String getTransmissionPowerDescriptionByParams(byte transmissionPower)
{
switch (transmissionPower)
{
case POWER_27:
return F("27dBm (Default)");
break;
case POWER_24:
return F("24dBm");
break;
case POWER_21:
return F("21dBm");
break;
case POWER_18:
return F("18dBm");
break;
default:
return F("Invalid transmission power param");
}
}
#elif defined(E32_TTL_1W)
enum TRANSMISSION_POWER
{
POWER_30 = B00,
POWER_27 = B01,
POWER_24 = B10,
POWER_21 = B11
};
static String getTransmissionPowerDescriptionByParams(byte transmissionPower)
{
switch (transmissionPower)
{
case POWER_30:
return F("30dBm (Default)");
break;
case POWER_27:
return F("27dBm");
break;
case POWER_24:
return F("24dBm");
break;
case POWER_21:
return F("21dBm");
break;
default:
return F("Invalid transmission power param");
}
}
#else
enum TRANSMISSION_POWER
{
POWER_20 = B00,
POWER_17 = B01,
POWER_14 = B10,
POWER_10 = B11
};
static String getTransmissionPowerDescriptionByParams(byte transmissionPower)
{
switch (transmissionPower)
{
case POWER_20:
return F("20dBm (Default)");
break;
case POWER_17:
return F("17dBm");
break;
case POWER_14:
return F("14dBm");
break;
case POWER_10:
return F("10dBm");
break;
default:
return F("Invalid transmission power param");
}
}
#endif
Loading…
Cancel
Save