Browse Source

Working

master
Englebert 4 years ago
parent
commit
9fc6749e74
  1. 675
      LoRa_E32.cpp
  2. 298
      LoRa_E32.h
  3. 461
      OpenFlightRX.ino
  4. 1567
      RF24.cpp
  5. 2072
      RF24.h
  6. 187
      RF24_config.h
  7. 128
      nRF24L01.h
  8. 42
      printf.h
  9. 452
      statesNaming.h

675
LoRa_E32.cpp

@ -1,675 +0,0 @@
#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(10);
// 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(20);
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(3);
// 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

@ -1,298 +0,0 @@
/*
* 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

461
OpenFlightRX.ino

@ -7,13 +7,21 @@
* 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"
// For NRF24L01 (E01) - EByte
// #include "nRF24L01.h"
#include "RF24.h"
#include "printf.h"
// Declaration for NRF24L01
#define MAX_CHANNELS 125
#define NRF24_CE 5 // GPIO5 (CE)
#define NRF24_CSN 4 // GPIO4 (CSN)
const uint64_t pipeIn = 0xE8E8F0F0E1LL; // Must be same as the transmissiona
RF24 radio(NRF24_CE, NRF24_CSN); // Starting up the module on GPIO5 (CE), GPIO4 (CSN)
// Debugging over telnet
#include <WiFi.h>
@ -23,54 +31,87 @@
const char* ssid = "M5LoRa";
const char* password = "LetMeIn";
WiFiServer server(23);
// WiFiServer server(23);
WiFiClient wifiClient; // Socket Handler
// 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
LoRa_E32 e32ttl100(Serial2);
#define INDICATOR 2
// LoRa related all on Core 0
TaskHandle_t LoraTask;
TaskHandle_t NRFTask;
// Temporary hardcode Address...
// 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;
void printParameters(struct Configuration configuration);
void printModuleInformation(struct ModuleInformation moduleInformation);
void setup_lora(void);
void telnet_server(void);
struct RxMessage {
uint16_t throttle;
uint16_t yaw;
uint16_t pitch;
uint16_t roll;
uint8_t switches;
};
RxMessage rxmessage;
// SBUS data structure
#define RC_CHANNEL_MIN 990
#define RC_CHANNEL_MAX 2010
#define SBUS_MIN_OFFSET 173
#define SBUS_MID_OFFSET 992
#define SBUS_MAX_OFFSET 1811
#define SBUS_CHANNEL_NUMBER 16
#define SBUS_PACKET_LENGTH 25
#define SBUS_FRAME_HEADER 0x0f
#define SBUS_FRAME_FOOTER 0x00
#define SBUS_FRAME_FOOTER_V2 0x04
#define SBUS_STATE_FAILSAFE 0x08
#define SBUS_STATE_SIGNALLOSS 0x04
#define SBUS_UPDATE_RATE 15 // ms
uint8_t sbusPacket[SBUS_PACKET_LENGTH];
int rcChannels[SBUS_CHANNEL_NUMBER];
uint32_t sbusTime = 0;
bool signalNotOK = false;
void setup_nrf_rx(void);
void socket_client(void);
void lora_recv(void);
void sbusPreparePacket(uint8_t packet[], int channels[], bool isSignalLoss, bool isFailsafe);
void setPPMValuesFromData(void);
void resetData(void);
int lora_received_count_raw = 0;
int lora_received_count = 0;
int nrf_received_count = 0;
int nrf_received_count_raw = 0;
uint32_t last_seconds = 0;
uint32_t last_telnet_seconds = 0;
bool ip_shown = false;
bool socket_connected = true;
bool nrf_enable = true;
uint32_t uptime = 0;
uint32_t nrf_last_receive = 0;
void setup() {
// For USB Debugging
Serial.begin(115200);
// LoRa Setup
setup_lora();
// For SBUS to FC
Serial2.begin(100000, SERIAL_8E2);
// Signal...
pinMode(INDICATOR, OUTPUT);
// Reset Data
resetData();
// NRF Setup
setup_nrf_rx();
// Temporary TX
// setup_lora_tx();
// WiFi Setup
// WiFi.begin(ssid, password);
@ -79,26 +120,37 @@ void setup() {
// Telnet
// server.begin();
// server.setNoDelay(true);
// Create 2nd task on core 0 for SBUS and NRF
xTaskCreatePinnedToCore(
NRFTasker, /* Task function. */
"NRFTasker", /* name of task. */
10000, /* Stack size of task */
NULL, /* parameter of the task */
0, /* priority of the task */
&NRFTask, /* Task handle to keep track of created task */
0); /* Pin task to Core 0 */
}
void loop() {
// Each seconds tick
if(millis() > last_seconds) {
lora_received_count = lora_received_count_raw;
lora_received_count_raw = 0;
nrf_received_count = nrf_received_count_raw;
nrf_received_count_raw = 0;
last_seconds = millis() + 1000;
uptime++;
Serial.print(F("LoRA:"));
Serial.println(lora_received_count);
Serial.print(F("NRF:"));
Serial.println(nrf_received_count);
if (WiFi.status() == WL_CONNECTED && ip_shown == false) {
Serial.println(WiFi.localIP());
ip_shown = true;
}
}
lora_recv();
nrf_recv();
socket_client();
// telnet_server();
@ -115,7 +167,7 @@ void socket_client(void) {
if(wifiClient.connected()) {
Serial.println("Sent Data to Screen");
char post_body[16];
sprintf(post_body, "RATE:%d", lora_received_count);
sprintf(post_body, "RATE:%d - %d", nrf_received_count, uptime);
wifiClient.write(post_body);
} else {
if(!wifiClient.connect(host, port, 2000)){
@ -149,228 +201,143 @@ void socket_client(void) {
}
}
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++;
}
}
void nrf_recv(void) {
/***** NRF ***/
if(radio.available()){
// Getting signals from NRF24L01
radio.read(&rxmessage, sizeof(RxMessage));
//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[32];
// 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;
// }
//
// } else {
// // Serial.println("WiFi not connected!");
// /*
// for(i = 0; i < MAX_SRV_CLIENTS; i++) {
// if (serverClients[i]) serverClients[i].stop();
// }
// delay(10);
// */
// }
//}
void setup_lora() {
// Startup all pins and UART
e32ttl100.begin();
ResponseStructContainer c;
c = e32ttl100.getConfiguration();
// 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);
printParameters(configuration);
/****** Setting up E32 Parameters *****/
// Communication address
configuration.ADDL = ADDR_L;
configuration.ADDH = ADDR_H;
// 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);
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 */
//
}
// Push to variables... and prepare for the SBUS signals...
setPPMValuesFromData();
ResponseStructContainer rsc;
// NRF profiling...
nrf_received_count_raw++;
nrf_last_receive = millis();
// Turns on.... LED
digitalWrite(INDICATOR, HIGH);
} else {
digitalWrite(INDICATOR, LOW);
}
}
void RecvLoRaSignals(void *pvParameters) {
// Sending SBUS signals
void NRFTasker(void *pvParameters) {
// Forever loop in this loop :P
for(;;) {
/***** LORA ***/
if(e32ttl100.available() > 1){
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);
if(millis() > sbusTime) {
sbusPreparePacket(sbusPacket, rcChannels, signalNotOK, false);
Serial2.write(sbusPacket, SBUS_PACKET_LENGTH);
// Prevent overflow. If on for more than 50 days
sbusTime = (uint32_t) (millis() + SBUS_UPDATE_RATE);
}
/*
// Script way for delay....
unsigned long t = millis();
while((millis() - t) < 100) {
}
*/
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());
// SBUS packets
void sbusPreparePacket(uint8_t packet[], int channels[], bool isSignalLoss, bool isFailsafe){
static int output[SBUS_CHANNEL_NUMBER] = {0};
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());
/*
* Map 1000-2000 with middle at 1500 chanel values to
* 173-1811 with middle at 992 S.BUS protocol requires
*/
for (uint8_t i = 0; i < SBUS_CHANNEL_NUMBER; i++) {
output[i] = map(channels[i], RC_CHANNEL_MIN, RC_CHANNEL_MAX, SBUS_MIN_OFFSET, SBUS_MAX_OFFSET);
}
Serial.println("----------------------------------------");
uint8_t stateByte = 0x00;
if (isSignalLoss) {
stateByte |= SBUS_STATE_SIGNALLOSS;
}
if (isFailsafe) {
stateByte |= SBUS_STATE_FAILSAFE;
}
packet[0] = SBUS_FRAME_HEADER; //Header
packet[1] = (uint8_t) (output[0] & 0x07FF);
packet[2] = (uint8_t) ((output[0] & 0x07FF)>>8 | (output[1] & 0x07FF)<<3);
packet[3] = (uint8_t) ((output[1] & 0x07FF)>>5 | (output[2] & 0x07FF)<<6);
packet[4] = (uint8_t) ((output[2] & 0x07FF)>>2);
packet[5] = (uint8_t) ((output[2] & 0x07FF)>>10 | (output[3] & 0x07FF)<<1);
packet[6] = (uint8_t) ((output[3] & 0x07FF)>>7 | (output[4] & 0x07FF)<<4);
packet[7] = (uint8_t) ((output[4] & 0x07FF)>>4 | (output[5] & 0x07FF)<<7);
packet[8] = (uint8_t) ((output[5] & 0x07FF)>>1);
packet[9] = (uint8_t) ((output[5] & 0x07FF)>>9 | (output[6] & 0x07FF)<<2);
packet[10] = (uint8_t) ((output[6] & 0x07FF)>>6 | (output[7] & 0x07FF)<<5);
packet[11] = (uint8_t) ((output[7] & 0x07FF)>>3);
packet[12] = (uint8_t) ((output[8] & 0x07FF));
packet[13] = (uint8_t) ((output[8] & 0x07FF)>>8 | (output[9] & 0x07FF)<<3);
packet[14] = (uint8_t) ((output[9] & 0x07FF)>>5 | (output[10] & 0x07FF)<<6);
packet[15] = (uint8_t) ((output[10] & 0x07FF)>>2);
packet[16] = (uint8_t) ((output[10] & 0x07FF)>>10 | (output[11] & 0x07FF)<<1);
packet[17] = (uint8_t) ((output[11] & 0x07FF)>>7 | (output[12] & 0x07FF)<<4);
packet[18] = (uint8_t) ((output[12] & 0x07FF)>>4 | (output[13] & 0x07FF)<<7);
packet[19] = (uint8_t) ((output[13] & 0x07FF)>>1);
packet[20] = (uint8_t) ((output[13] & 0x07FF)>>9 | (output[14] & 0x07FF)<<2);
packet[21] = (uint8_t) ((output[14] & 0x07FF)>>6 | (output[15] & 0x07FF)<<5);
packet[22] = (uint8_t) ((output[15] & 0x07FF)>>3);
// TODO.... may need to add two more channels...(FUTURE DEVELOPMENT)
packet[23] = stateByte; //Flags byte
packet[24] = SBUS_FRAME_FOOTER; //Footer
}
void setPPMValuesFromData(void) {
/*
* The values for:
* - throttle
* - yaw
* - pitch
* - roll
*/
rcChannels[2] = rxmessage.throttle; // Throttle
rcChannels[3] = rxmessage.yaw; // Yaw
rcChannels[1] = rxmessage.pitch; // Pitch
rcChannels[0] = rxmessage.roll; // Roll
rcChannels[4] = 1000; // Channel C
// Misc: (64 * channel_a) | (32 * channel_b) | (16 * channel_d) | (8 * channel_e) | (4 * channel_f) | (2 * channel_g) | (1 * channel_h);
// ch6 reserved for the moment
// Processing switches channel....
rcChannels[5] = (rxmessage.switches & (1 << 0)) ? 2000 : 1000;
rcChannels[6] = (rxmessage.switches & (1 << 1)) ? 2000 : 1000;
rcChannels[7] = (rxmessage.switches & (1 << 2)) ? 2000 : 1000;
rcChannels[8] = (rxmessage.switches & (1 << 3)) ? 2000 : 1000;
rcChannels[9] = (rxmessage.switches & (1 << 4)) ? 2000 : 1000;
rcChannels[10] = (rxmessage.switches & (1 << 5)) ? 2000 : 1000;
rcChannels[11] = (rxmessage.switches & (1 << 6)) ? 2000 : 1000;
rcChannels[12] = (rxmessage.switches & (1 << 7)) ? 2000 : 1000;
rcChannels[13] = 1000; // Not in use
rcChannels[14] = 1000; // Not in use
rcChannels[15] = 1000; // Not in use
}
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("----------------------------------------");
void resetData(void) {
rxmessage.throttle = 900;
rxmessage.yaw = 900;
rxmessage.pitch = 900;
rxmessage.roll = 900;
rxmessage.switches = 0;
setPPMValuesFromData();
}
void setup_nrf_rx(void) {
radio.begin();
radio.setAutoAck(false);
radio.setChannel(99); // Temporary at 99. Later read from EEPROM
radio.setPayloadSize(sizeof(RxMessage));
radio.setDataRate(RF24_250KBPS);
radio.openReadingPipe(1, pipeIn); // Change this too.
radio.startListening();
}

1567
RF24.cpp
File diff suppressed because it is too large
View File

2072
RF24.h
File diff suppressed because it is too large
View File

187
RF24_config.h

@ -0,0 +1,187 @@
/*
Copyright (C)
2011 J. Coliz <maniacbug@ymail.com>
2015-2019 TMRh20
2015 spaniakos <spaniakos@gmail.com>
2015 nerdralph
2015 zador-blood-stained
2016 akatran
2017-2019 Avamander <avamander@gmail.com>
2019 IkpeohaGodson
This program is free software; you can redistribute it and/or
modify it under the terms of the GNU General Public License
version 2 as published by the Free Software Foundation.
*/
#ifndef __RF24_CONFIG_H__
#define __RF24_CONFIG_H__
/*** USER DEFINES: ***/
#define FAILURE_HANDLING
//#define SERIAL_DEBUG
//#define MINIMAL
//#define SPI_UART // Requires library from https://github.com/TMRh20/Sketches/tree/master/SPI_UART
//#define SOFTSPI // Requires library from https://github.com/greiman/DigitalIO
/**********************/
#define rf24_max(a,b) (a>b?a:b)
#define rf24_min(a,b) (a<b?a:b)
#define RF24_SPI_SPEED 10000000
//ATXMega
#if defined (__AVR_ATxmega64D3__) || defined (__AVR_ATxmega128D3__) || defined (__AVR_ATxmega192D3__) || defined (__AVR_ATxmega256D3__) || defined (__AVR_ATxmega384D3__) // In order to be available both in Windows and Linux this should take presence here.
#define XMEGA
#define XMEGA_D3
#include "utility/ATXMegaD3/RF24_arch_config.h"
#elif ( !defined (ARDUINO) ) // Any non-arduino device is handled via configure/Makefile
// The configure script detects device and copies the correct includes.h file to /utility/includes.h
// This behavior can be overridden by calling configure with respective parameters
// The includes.h file defines either RF24_RPi, MRAA, LITTLEWIRE or RF24_SPIDEV and includes the correct RF24_arch_config.h file
#include "utility/includes.h"
//ATTiny
#elif defined (__AVR_ATtiny25__) || defined (__AVR_ATtiny45__) || defined (__AVR_ATtiny85__) || defined (__AVR_ATtiny24__) || defined (__AVR_ATtiny44__) || defined (__AVR_ATtiny84__) || defined (__AVR_ATtiny2313__) || defined (__AVR_ATtiny4313__) || defined (__AVR_ATtiny861__)
#define RF24_TINY
#include "utility/ATTiny/RF24_arch_config.h"
#elif defined (LITTLEWIRE) //LittleWire
#include "utility/LittleWire/RF24_arch_config.h"
#elif defined (TEENSYDUINO) //Teensy
#include "utility/Teensy/RF24_arch_config.h"
#else //Everything else
#include <Arduino.h>
#if defined (ARDUINO) && !defined (__arm__) && !defined (__ARDUINO_X86__)
#if defined SPI_UART
#include <SPI_UART.h>
#define _SPI uspi
#elif defined (SOFTSPI)
// change these pins to your liking
//
#ifndef SOFT_SPI_MISO_PIN
#define SOFT_SPI_MISO_PIN 9
#endif // SOFT_SPI_MISO_PIN
#ifndef SOFT_SPI_MOSI_PIN
#define SOFT_SPI_MOSI_PIN 8
#endif // SOFT_SPI_MOSI_PIN
#ifndef SOFT_SPI_SCK_PIN
#define SOFT_SPI_SCK_PIN 7
#endif // SOFT_SPI_SCK_PIN
const uint8_t SPI_MODE = 0;
#define _SPI spi
#else // !defined (SPI_UART) && !defined (SOFTSPI)
#include <SPI.h>
#define _SPI SPI
#endif // !defined (SPI_UART) && !defined (SOFTSPI)
#else // defined (ARDUINO) && !defined (__arm__) && !defined (__ARDUINO_X86__)
// Define _BV for non-Arduino platforms and for Arduino DUE
#include <stdint.h>
#include <stdio.h>
#include <string.h>
#if defined(__arm__) || defined (__ARDUINO_X86__)
#if defined (__arm__) && defined (SPI_UART)
#include <SPI_UART.h>
#define _SPI uspi
#else // !defined (__arm__) || !defined (SPI_UART)
#include <SPI.h>
#define _SPI SPI
#endif // !defined (__arm__) || !defined (SPI_UART)
#elif !defined(__arm__) && !defined (__ARDUINO_X86__)
extern HardwareSPI SPI;
#endif // !defined(__arm__) && !defined (__ARDUINO_X86__)
#ifndef _BV
#define _BV(x) (1<<(x))
#endif
#endif // defined (ARDUINO) && !defined (__arm__) && !defined (__ARDUINO_X86__)
#ifdef SERIAL_DEBUG
#define IF_SERIAL_DEBUG(x) ({x;})
#else
#define IF_SERIAL_DEBUG(x)
#if defined(RF24_TINY)
#define printf_P(...)
#endif // defined(RF24_TINY)
#endif // SERIAL_DEBUG
#if defined (__ARDUINO_X86__)
#define printf_P printf
#define _BV(bit) (1<<(bit))
#endif // defined (__ARDUINO_X86__)
// Progmem is Arduino-specific
// Arduino DUE is arm and does not include avr/pgmspace
#if defined (ARDUINO_ARCH_ESP8266) || defined (ESP32)
#include <pgmspace.h>
#define PRIPSTR "%s"
#ifndef pgm_read_ptr
#define pgm_read_ptr(p) (*(p))
#endif
#elif defined (ARDUINO) && !defined (ESP_PLATFORM) && ! defined (__arm__) && !defined (__ARDUINO_X86__) || defined (XMEGA)
#include <avr/pgmspace.h>
#define PRIPSTR "%S"
#else // !defined (ARDUINO) || defined (ESP_PLATFORM) || defined (__arm__) || defined (__ARDUINO_X86__) && !defined (XMEGA)
#if !defined (ARDUINO) // This doesn't work on Arduino DUE
typedef char const char;
#else // Fill in pgm_read_byte that is used, but missing from DUE
#ifdef ARDUINO_ARCH_AVR
#include <avr/pgmspace.h>
#endif
#ifndef pgm_read_byte
#define pgm_read_byte(addr) (*(const unsigned char *)(addr))
#endif
#endif // !defined (ARDUINO)
#ifndef prog_uint16_t
typedef uint16_t prog_uint16_t;
#endif
#ifndef PSTR
#define PSTR(x) (x)
#endif
#ifndef printf_P
#define printf_P printf
#endif
#ifndef strlen_P
#define strlen_P strlen
#endif
#ifndef PROGMEM
#define PROGMEM
#endif
#ifndef pgm_read_word
#define pgm_read_word(p) (*(p))
#endif
#if !defined pgm_read_ptr || defined ARDUINO_ARCH_MBED
#define pgm_read_ptr(p) (*(p))
#endif
#ifndef PRIPSTR
#define PRIPSTR "%s"
#endif
#endif // !defined (ARDUINO) || defined (ESP_PLATFORM) || defined (__arm__) || defined (__ARDUINO_X86__) && !defined (XMEGA)
#endif //Everything else
#if defined (SPI_HAS_TRANSACTION) && !defined (SPI_UART) && !defined (SOFTSPI)
#define RF24_SPI_TRANSACTIONS
#endif // defined (SPI_HAS_TRANSACTION) && !defined (SPI_UART) && !defined (SOFTSPI)
#endif // __RF24_CONFIG_H__

128
nRF24L01.h

@ -0,0 +1,128 @@
/*
Copyright (c) 2007 Stefan Engelke <mbox@stefanengelke.de>
Portions Copyright (C) 2011 Greg Copeland
Permission is hereby granted, free of charge, to any person
obtaining a copy of this software and associated documentation
files (the "Software"), to deal in the Software without
restriction, including without limitation the rights to use, copy,
modify, merge, publish, distribute, sublicense, and/or sell copies
of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be
included in all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT
HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY,
WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
DEALINGS IN THE SOFTWARE.
*/
/* Memory Map */
#define NRF_CONFIG 0x00
#define EN_AA 0x01
#define EN_RXADDR 0x02
#define SETUP_AW 0x03
#define SETUP_RETR 0x04
#define RF_CH 0x05
#define RF_SETUP 0x06
#define NRF_STATUS 0x07
#define OBSERVE_TX 0x08
#define CD 0x09
#define RX_ADDR_P0 0x0A
#define RX_ADDR_P1 0x0B
#define RX_ADDR_P2 0x0C
#define RX_ADDR_P3 0x0D
#define RX_ADDR_P4 0x0E
#define RX_ADDR_P5 0x0F
#define TX_ADDR 0x10
#define RX_PW_P0 0x11
#define RX_PW_P1 0x12
#define RX_PW_P2 0x13
#define RX_PW_P3 0x14
#define RX_PW_P4 0x15
#define RX_PW_P5 0x16
#define FIFO_STATUS 0x17
#define DYNPD 0x1C
#define FEATURE 0x1D
/* Bit Mnemonics */
#define MASK_RX_DR 6
#define MASK_TX_DS 5
#define MASK_MAX_RT 4
#define EN_CRC 3
#define CRCO 2
#define PWR_UP 1
#define PRIM_RX 0
#define ENAA_P5 5
#define ENAA_P4 4
#define ENAA_P3 3
#define ENAA_P2 2
#define ENAA_P1 1
#define ENAA_P0 0
#define ERX_P5 5
#define ERX_P4 4
#define ERX_P3 3
#define ERX_P2 2
#define ERX_P1 1
#define ERX_P0 0
#define AW 0
#define ARD 4
#define ARC 0
#define PLL_LOCK 4
#define CONT_WAVE 7
#define RF_DR 3
#define RF_PWR 6
#define RX_DR 6
#define TX_DS 5
#define MAX_RT 4
#define RX_P_NO 1
#define TX_FULL 0
#define PLOS_CNT 4
#define ARC_CNT 0
#define TX_REUSE 6
#define FIFO_FULL 5
#define TX_EMPTY 4
#define RX_FULL 1
#define RX_EMPTY 0
#define DPL_P5 5
#define DPL_P4 4
#define DPL_P3 3
#define DPL_P2 2
#define DPL_P1 1
#define DPL_P0 0
#define EN_DPL 2
#define EN_ACK_PAY 1
#define EN_DYN_ACK 0
/* Instruction Mnemonics */
#define R_REGISTER 0x00
#define W_REGISTER 0x20
#define REGISTER_MASK 0x1F
#define ACTIVATE 0x50
#define R_RX_PL_WID 0x60
#define R_RX_PAYLOAD 0x61
#define W_TX_PAYLOAD 0xA0
#define W_ACK_PAYLOAD 0xA8
#define FLUSH_TX 0xE1
#define FLUSH_RX 0xE2
#define REUSE_TX_PL 0xE3
#define RF24_NOP 0xFF
/* Non-P omissions */
#define LNA_HCURR 0
/* P model memory Map */
#define RPD 0x09
#define W_TX_PAYLOAD_NO_ACK 0xB0
/* P model bit Mnemonics */
#define RF_DR_LOW 5
#define RF_DR_HIGH 3
#define RF_PWR_LOW 1
#define RF_PWR_HIGH 2

42
printf.h

@ -0,0 +1,42 @@
/*
Copyright (C) 2011 J. Coliz <maniacbug@ymail.com>
This program is free software; you can redistribute it and/or
modify it under the terms of the GNU General Public License
version 2 as published by the Free Software Foundation.
*/
/* Galileo support from spaniakos <spaniakos@gmail.com> */
/**
* @file printf.h
*
* Setup necessary to direct stdout to the Arduino Serial library, which
* enables 'printf'
*/
#ifndef __PRINTF_H__
#define __PRINTF_H__
#if defined(ARDUINO_ARCH_AVR) || defined(__ARDUINO_X86__)
int serial_putc(char c, FILE *)
{
Serial.write(c);
return c;
}
#endif
void printf_begin(void)
{
#if defined(ARDUINO_ARCH_AVR)
fdevopen(&serial_putc, 0);
#elif defined(__ARDUINO_X86__)
// JESUS - For reddirect stdout to /dev/ttyGS0 (Serial Monitor port)
stdout = freopen("/dev/ttyGS0", "w", stdout);
delay(500);
printf("Redirecting to Serial...");
#endif // defined(__ARDUINO_X86__)
}
#endif // __PRINTF_H__

452
statesNaming.h

@ -1,452 +0,0 @@
#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