diff --git a/include/README b/include/README new file mode 100644 index 0000000..194dcd4 --- /dev/null +++ b/include/README @@ -0,0 +1,39 @@ + +This directory is intended for project header files. + +A header file is a file containing C declarations and macro definitions +to be shared between several project source files. You request the use of a +header file in your project source file (C, C++, etc) located in `src` folder +by including it, with the C preprocessing directive `#include'. + +```src/main.c + +#include "header.h" + +int main (void) +{ + ... +} +``` + +Including a header file produces the same results as copying the header file +into each source file that needs it. Such copying would be time-consuming +and error-prone. With a header file, the related declarations appear +in only one place. If they need to be changed, they can be changed in one +place, and programs that include the header file will automatically use the +new version when next recompiled. The header file eliminates the labor of +finding and changing all the copies as well as the risk that a failure to +find one copy will result in inconsistencies within a program. + +In C, the usual convention is to give header files names that end with `.h'. +It is most portable to use only letters, digits, dashes, and underscores in +header file names, and at most one dot. + +Read more about using header files in official GCC documentation: + +* Include Syntax +* Include Operation +* Once-Only Headers +* Computed Includes + +https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html diff --git a/lib/README b/lib/README new file mode 100644 index 0000000..6debab1 --- /dev/null +++ b/lib/README @@ -0,0 +1,46 @@ + +This directory is intended for project specific (private) libraries. +PlatformIO will compile them to static libraries and link into executable file. + +The source code of each library should be placed in a an own separate directory +("lib/your_library_name/[here are source files]"). + +For example, see a structure of the following two libraries `Foo` and `Bar`: + +|--lib +| | +| |--Bar +| | |--docs +| | |--examples +| | |--src +| | |- Bar.c +| | |- Bar.h +| | |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html +| | +| |--Foo +| | |- Foo.c +| | |- Foo.h +| | +| |- README --> THIS FILE +| +|- platformio.ini +|--src + |- main.c + +and a contents of `src/main.c`: +``` +#include +#include + +int main (void) +{ + ... +} + +``` + +PlatformIO Library Dependency Finder will find automatically dependent +libraries scanning project source files. + +More information about PlatformIO Library Dependency Finder +- https://docs.platformio.org/page/librarymanager/ldf.html diff --git a/platformio.ini b/platformio.ini new file mode 100644 index 0000000..979b747 --- /dev/null +++ b/platformio.ini @@ -0,0 +1,19 @@ +; PlatformIO Project Configuration File +; +; Build options: build flags, source filter +; Upload options: custom upload port, speed and extra flags +; Library options: dependencies, extra library storages +; Advanced options: extra scripting +; +; Please visit documentation for the other options and examples +; https://docs.platformio.org/page/projectconf.html + +[env:esp12e] +platform = espressif8266 +board = esp12e +framework = arduino +; Comment out if upload via USB. Now is via OTA +upload_protocol = espota +upload_port = 192.168.4.1 +board_build.filesystem = littlefs +lib_deps = arkhipenko/TaskScheduler@^3.6.0 diff --git a/src/CustomWiFi.cpp b/src/CustomWiFi.cpp new file mode 100644 index 0000000..b5b20d9 --- /dev/null +++ b/src/CustomWiFi.cpp @@ -0,0 +1,35 @@ +#include "CustomWiFi.h" + +CustomWiFi::CustomWiFi(void) { + // pinMode(CustomWiFi_INDICATOR, OUTPUT); + last_wifi_check = 0; + wifi_check_duration = 10; +} + +void CustomWiFi::set_credential(char *ssid, char *passphrase) { + strcpy(CustomWiFi::_ssid, ssid); + strcpy(CustomWiFi::_passphrase, passphrase); + + // Initial value + this->wifi_check_duration = 5000; +} + + +void CustomWiFi::begin(void) { + IPAddress local_ip(192,168,4,1); + IPAddress gateway(192,168,4,1); + IPAddress subnet(255,255,255,0); + + + // WiFi.softAPConfig(local_IP, gateway, subnet); + WiFi.softAPConfig(local_ip, gateway, subnet); + WiFi.softAP("SIMPLERX"); + // WiFi.softAP(WIFI_SSID, WIFI_PASSPHRASE); + Serial.println(WiFi.softAPIP()); + delay(100); + + // IPAddress IP = WiFi.softAPIP(); + // Serial.print(F("AP IP address: "); Serial.prinln(IP); +} + +CustomWiFi customwifi; diff --git a/src/CustomWiFi.h b/src/CustomWiFi.h new file mode 100644 index 0000000..26d8cd4 --- /dev/null +++ b/src/CustomWiFi.h @@ -0,0 +1,20 @@ +#ifndef CUSTOMWIFI_H_ +#define CUSTOMWIFI_H_ + +#include +#include +// #include + +class CustomWiFi { + public: + CustomWiFi(void); + void set_credential(char *ssid, char *passphrase); + void begin(void); + char _ssid[32], _passphrase[32]; + + private: + uint32_t last_wifi_check, wifi_check_duration; +}; + +extern CustomWiFi customwifi; +#endif diff --git a/src/OTA.cpp b/src/OTA.cpp new file mode 100644 index 0000000..ecda278 --- /dev/null +++ b/src/OTA.cpp @@ -0,0 +1,49 @@ +#include "OTA.h" + +OTA::OTA(void) { +} + +void OTA::begin(void) { + ArduinoOTA.begin(); + + // Set Port to 8266 + ArduinoOTA.setPort(8266); + + ArduinoOTA.onStart([]() { + String type; + if(ArduinoOTA.getCommand() == U_FLASH) { + type = "sketch"; + } else { // U_FS + type = "filesystem"; + } + + // NOTE: if updating FS this would be the place to unmount FS using FS.end() + Serial.println("Start updating " + type); + }); + ArduinoOTA.onEnd([]() { + Serial.println("\nEnd"); + }); + ArduinoOTA.onProgress([](unsigned int progress, unsigned int total) { + Serial.printf("Progress: %u%%\r", (progress / (total / 100))); + }); + ArduinoOTA.onError([](ota_error_t error) { + Serial.printf("Error[%u]: ", error); + if(error == OTA_AUTH_ERROR) { + Serial.println("Auth Failed"); + } else if(error == OTA_BEGIN_ERROR) { + Serial.println("Begin Failed"); + } else if(error == OTA_CONNECT_ERROR) { + Serial.println("Connect Failed"); + } else if(error == OTA_RECEIVE_ERROR) { + Serial.println("Receive Failed"); + } else if(error == OTA_END_ERROR) { + Serial.println("End Failed"); + } + }); +} + +void OTA::run(void) { + ArduinoOTA.handle(); +} + +OTA ota; diff --git a/src/OTA.h b/src/OTA.h new file mode 100644 index 0000000..b573bb6 --- /dev/null +++ b/src/OTA.h @@ -0,0 +1,18 @@ +#ifndef OTA_H_ +#define OTA_H_ + +#include +#include + +class OTA { + public: + OTA(void); + void begin(void); + void run(void); + + private: + uint32_t last_wifi_check, wifi_check_duration; +}; + +extern OTA ota; +#endif diff --git a/src/Storage.cpp b/src/Storage.cpp new file mode 100644 index 0000000..e770b73 --- /dev/null +++ b/src/Storage.cpp @@ -0,0 +1,236 @@ +#include "Storage.h" + +// REF: +// https://github.com/pbecchi/ESP32-Sprinkler/blob/master/Eeprom_ESP.cpp + +Storage::Storage(void) { + // Just some initialization +} + + +bool Storage::format(void) { + // if(LITTLEFS.format()) { + if(LittleFS.format()) { + return true; + } else { + return false; + } +} + + +bool Storage::exists(const char * path) { + // if(LITTLEFS.exists(path)) { + if(LittleFS.exists(path)) { + return true; + } else { + return false; + } +} + + +bool Storage::begin(void) { + // if(!LITTLEFS.begin(FORMAT_LITTLEFS_IF_FAILED)) { + if(!LittleFS.begin()) { + Serial.println("LITTLEFS mount failed"); + return false; + } + + // Demo and checking only + // Storage::listDir(LITTLEFS, "/", 0); + Storage::listDir(LittleFS, "/", 0); + + if(Storage::exists("/SIMPLERX")) { + Serial.println(F("SIMPLERX FOUND")); + } else { + Serial.println(F("SIMPLERX NOT FOUND - Formatting now")); + Storage::format(); + // Storage::writeFile(LITTLEFS, "/MSCoreTX", ""); + Storage::writeFile(LittleFS, "/SIMPLERX", ""); + load_defaults = true; + } + + // Check Total storage + // Serial.print(F("Storage size: ")); + // Serial.print(LITTLEFS.totalBytes()); + // Serial.print(LittleFS.totalBytes()); + // Serial.println(F(" Bytes")); + + // Serial.print(F("Storage used: " )); + // Serial.print(LITTLEFS.usedBytes()); + // Serial.print(LittleFS.usedBytes()); + // Serial.println(F(" Bytes")); + return true; +} + + +void Storage::listDir(fs::FS &fs, const char * dirname, uint8_t levels){ + Serial.printf("Listing directory: %s\r\n", dirname); + + File root = fs.open(dirname, "r"); + if(!root){ + Serial.println(F("- failed to open directory")); + return; + } + if(!root.isDirectory()){ + Serial.println(F(" - not a directory")); + return; + } + + File file = root.openNextFile(); + while(file){ + if(file.isDirectory()){ + Serial.print(F(" DIR : ")); + + #ifdef CONFIG_LITTLEFS_FOR_IDF_3_2 + Serial.println(file.name()); + #else + Serial.print(file.name()); + time_t t= file.getLastWrite(); + struct tm * tmstruct = localtime(&t); + Serial.printf(" LAST WRITE: %d-%02d-%02d %02d:%02d:%02d\n",(tmstruct->tm_year)+1900,( tmstruct->tm_mon)+1, tmstruct->tm_mday,tmstruct->tm_hour , tmstruct->tm_min, tmstruct->tm_sec); + #endif + + if(levels){ + listDir(fs, file.name(), levels -1); + } + } else { + Serial.print(F(" FILE: ")); + Serial.print(file.name()); + Serial.print(F(" SIZE: ")); + + #ifdef CONFIG_LITTLEFS_FOR_IDF_3_2 + Serial.println(file.size()); + #else + Serial.print(file.size()); + time_t t= file.getLastWrite(); + struct tm * tmstruct = localtime(&t); + Serial.printf(" LAST WRITE: %d-%02d-%02d %02d:%02d:%02d\n",(tmstruct->tm_year)+1900,( tmstruct->tm_mon)+1, tmstruct->tm_mday,tmstruct->tm_hour , tmstruct->tm_min, tmstruct->tm_sec); + #endif + } + file = root.openNextFile(); + } +} + + +void Storage::readFile(fs::FS &fs, const char * path){ + Serial.printf("Reading file: %s\r\n", path); + + File file = fs.open(path, "r"); + if(!file || file.isDirectory()){ + Serial.println(F("- failed to open file for reading")); + return; + } + + Serial.println(F("- read from file:")); + while(file.available()){ + Serial.write(file.read()); + } + file.close(); +} + + +void Storage::appendFile(fs::FS &fs, const char * path, const char * message){ + Serial.printf("Appending to file: %s\r\n", path); + + File file = fs.open(path, "w+"); + if(!file){ + Serial.println("- failed to open file for appending"); + return; + } + if(file.print(message)){ + Serial.println("- message appended"); + } else { + Serial.println("- append failed"); + } + file.close(); +} + + +void Storage::deleteFile(fs::FS &fs, const char * path){ + Serial.printf("Deleting file: %s\r\n", path); + if(fs.remove(path)){ + Serial.println("- file deleted"); + } else { + Serial.println("- delete failed"); + } +} + + +void Storage::writeFile(fs::FS &fs, const char * path, const char * message){ + Serial.printf("Writing file: %s\r\n", path); + + File file = fs.open(path, "w+"); + if(!file){ + Serial.println("- failed to open file for writing"); + return; + } + + if(file.print(message)){ + Serial.println("- file written"); + } else { + Serial.println("- write failed"); + } + + file.close(); +} + + +//void Storage::write_block(uint8_t * data, const char * path, uint32_t len){ +void Storage::write_block(const void * data, const char * path, uint32_t len){ + uint32_t i; + // fs::FS &fs = LITTLEFS; + fs::FS &fs = LittleFS; + // Serial.println("write block 1"); + // Serial.print("FILE: "); + // Serial.println(path); + // Serial.println(ESP.getFreeHeap()); + + // File file = fs.open(path, FILE_WRITE); + File file = fs.open(path, "w+"); + // Serial.println("write block 2"); + if(!file) { + Serial.println("write_block append failed"); + return; + } + // Serial.println("write block 3"); + /** + for(i = 0; i < len; i++){ + // EEPROM.write(address+i, data[i]); + byte b = *((unsigned char*) data + i); + Serial.print("Wrote: "); Serial.println(b); + } + **/ + file.write((byte *)&data, sizeof(len)); + // Serial.println("write block 4"); + file.close(); +} + + +void Storage::read_block(void * data, const char * path, uint32_t len){ + uint32_t i; + // fs::FS &fs = LITTLEFS; + fs::FS &fs = LittleFS; + + File file = fs.open(path, "r"); + if(!file) { + Serial.println("- File not exists."); + return; + } + + // for(i = 0; i < len; i++){ + /** + i = 0; + while(file.available()) { + // data[i] = EEPROM.read(address+i); + // data[i++] = file.read(); + // uint8_t b = file.read() + *((char *)data + i) = file.read(); + Serial.print("read_block: "); Serial.println(*((char *)data + i)); + i++; + } + **/ + file.read((byte *)&data, sizeof(len)); + file.close(); +} + +Storage storage; diff --git a/src/Storage.h b/src/Storage.h new file mode 100644 index 0000000..e20d61e --- /dev/null +++ b/src/Storage.h @@ -0,0 +1,43 @@ +#ifndef _Storage_H +#define _Storage_H + +#include +// #include +#include + +#ifndef CONFIG_LITTLEFS_FOR_IDF_3_2 +#include +#endif + +/* You only need to format LITTLEFS the first time you run a + test or else use the LITTLEFS plugin to create a partition + https://github.com/lorol/arduino-esp32littlefs-plugin */ + +#define FORMAT_LITTLEFS_IF_FAILED true + + +class Storage { + + public: + Storage(void); + bool begin(void); + void listDir(fs::FS &fs, const char * dirname, uint8_t levels); + void readFile(fs::FS &fs, const char * path); + void appendFile(fs::FS &fs, const char * path, const char * message); + void deleteFile(fs::FS &fs, const char * path); + void writeFile(fs::FS &fs, const char * path, const char * message); + + // Emulate EEPROM write to LITTLEFS + // void write_block(uint8_t * data, const char * path, uint32_t len); + void write_block(const void * data, const char * path, uint32_t len); + void read_block(void * data, const char * path, uint32_t len); + + bool format(void); + bool exists(const char * path); + bool load_defaults = false; // Default false. Only during reset this will auto set to true + + private: +}; + +extern Storage storage; +#endif diff --git a/src/Web.cpp b/src/Web.cpp new file mode 100644 index 0000000..0a15b36 --- /dev/null +++ b/src/Web.cpp @@ -0,0 +1,160 @@ +#include "Web.h" + +// WebServer server(PORT_HTTP); +ESP8266WebServer server(80); +bool update_status = false; +bool opened = false; +File root; + +WEB::WEB(void){ +} + +void WEB::begin(void) { + // Allow CORS + // server.enableCORS(); + + // Index + server.on("/", HTTP_GET, []() { + // File html_handler = LITTLEFS.open("/index.html.gz", FILE_READ); + // server.streamFile(html_handler, "text/html"); + // html_handler.close(); + server.send(200, "text/html", "SimpleRX 0.1"); + server.sendHeader("Connection", "close"); + }); + + /*** Temporary disable update for ESP8266 + // Update + server.on("/update", HTTP_POST, []() { + server.sendHeader("Connection", "close"); + server.send(200, "text/plain", (Update.hasError()) ? "FAIL" : "OK. Device is rebooting"); + + if(Update.hasError()) { + update_status = false; + // web.set_update_status(false); + } else { + delay(1000); + ESP.restart(); + } + }, []() { + HTTPUpload& upload = server.upload(); + if(!update_status) + update_status = true; + + if(upload.status == UPLOAD_FILE_START) { + Serial.printf("Update: %s\n", upload.filename.c_str()); + + // Start with maximum available size + if(!Update.begin(UPDATE_SIZE_UNKNOWN)) + Update.printError(Serial); + } else if(upload.status == UPLOAD_FILE_WRITE) { + // Flashing firmware to ESP + if( + Update.write(upload.buf, upload.currentSize) != upload.currentSize + ) + Update.printError(Serial); + + } else if(upload.status == UPLOAD_FILE_END) { + if(Update.end(true)) + // True to set the size to the current progress + Serial.printf("Update Success: %u\nRebooting...\n", upload.totalSize); + else + Update.printError(Serial); + } + }); + ***/ + + // Reset + server.on("/reset", HTTP_GET, []() { + server.sendHeader("Connection", "close"); + server.send(200, "text/html", "1"); + // storage.deleteFile(LITTLEFS, "/MSCoreTX"); + storage.deleteFile(LittleFS, "/ADAM"); + delay(1000); + ESP.restart(); + }); + + // Reboot + server.on("/reboot", HTTP_GET, []() { + server.sendHeader("Connection", "close"); + server.send(200, "text/html", "1"); + delay(1000); + ESP.restart(); + }); + + // Remove files + server.on("/erase", HTTP_GET, []() { + String filename; + uint8_t detected = 0; + + for(uint8_t i = 0; i < server.args(); i++) { + String value = server.arg(i); + + if(server.argName(i) == "filename") { + filename = value; + detected++; + } + } + + server.sendHeader("Connection", "close"); + if(detected) { + // LITTLEFS.remove("/" + filename); + LittleFS.remove("/" + filename); + server.send(200, "text/plain", "REMOVED - [" + filename + "]"); + } else { + server.send(200, "text/plain", "Nothing remove."); + } + }); + + // TODO: create a way to upload files to the ESP32 and also handling it + // REF: https://techtutorialsx.com/2019/03/04/esp32-arduino-serving-bootstrap/ + // SPIFFS File upload + server.on("/webupload", HTTP_POST, []() { + server.sendHeader("Connection", "close"); + server.send(200, "text/plain", "webupload Done"); + }, []() { + HTTPUpload& upload = server.upload(); + + if(opened == false) { + opened = true; + // root = LITTLEFS.open((String("/") + upload.filename).c_str(), FILE_WRITE); + root = LittleFS.open((String("/") + upload.filename).c_str(), "w"); + if(!root) { + Serial.printf("Failed to open file for writing. [%s]\n", upload.filename.c_str()); + return; + } else { + Serial.println("Webupload file start."); + } + } + + if(upload.status == UPLOAD_FILE_START) { + Serial.printf("webupload: %s\n", upload.filename.c_str()); + } else if(upload.status == UPLOAD_FILE_WRITE) { + // Writting to SPIFFS + if(root.write(upload.buf, upload.currentSize) != upload.currentSize) { + Serial.printf("Failed to write. [%s]\n", upload.filename.c_str()); + return; + } + } else if(upload.status == UPLOAD_FILE_END) { + root.close(); + opened = false; + Serial.printf("webupload done. [%s]\n", upload.filename.c_str()); + + #ifdef DEBUG_MODE + Serial.printf("LITTLEFS Files:\n"); + // list_files(); + // storage.listDir(LITTLEFS, "/", 0); + storage.listDir(LittleFS, "/", 0); + #endif + + } + }); + + server.begin(); +} + +void WEB::handler(void) { + server.handleClient(); +} + + +WEB web; diff --git a/src/Web.h b/src/Web.h new file mode 100644 index 0000000..59df2e1 --- /dev/null +++ b/src/Web.h @@ -0,0 +1,25 @@ +#ifndef WEB_H_ +#define WEB_H_ + +#include +#include +#include "Storage.h" +// #include +// // #include +// #include +// // #include +// #include +// +#define PORT_HTTP 80 + +class WEB { + public: + WEB(void); + void begin(void); + void handler(void); + + private: +}; + +extern WEB web; +#endif diff --git a/src/main.cpp b/src/main.cpp new file mode 100644 index 0000000..08b1827 --- /dev/null +++ b/src/main.cpp @@ -0,0 +1,229 @@ +#include +// #define _TASK_TIMECRITICAL // Enable monitoring scheduling overruns +// #define _TASK_SLEEP_ON_IDLE_RUN // Enable 1 ms SLEEP_IDLE powerdowns between tasks if no callback methods were invoked during the pass +// #define _TASK_STATUS_REQUEST // Compile with support for StatusRequest functionality - triggering tasks on status change events in addition to time only +// #define _TASK_WDT_IDS // Compile with support for wdt control points and task ids +// #define _TASK_LTS_POINTER // Compile with support for local task storage pointer +// #define _TASK_PRIORITY // Support for layered scheduling priority +// #define _TASK_MICRO_RES // Support for microsecond resolution +// #define _TASK_STD_FUNCTION // Support for std::function (ESP8266 and ESP32 ONLY) +// #define _TASK_DEBUG // Make all methods and variables public for debug purposes +// #define _TASK_INLINE // Make all methods "inline" - needed to support some multi-tab, multi-file implementations +// #define _TASK_TIMEOUT // Support for overall task timeout +// #define _TASK_OO_CALLBACKS // Support for dynamic callback method binding +#include +#include "main.h" + +#define LED_STATUS 14 +#define LED_HEARTBEAT 2 +bool led_heartbeat_state = false; + +uint16_t rcCommand[18]; // Signal to ESC + +Scheduler scheduler; +RXMessage rxMessage; + +// Every 5 miliseconds +Task task_sbus_generator(10, TASK_FOREVER, &send_sbus); +Task task_rx(50, TASK_FOREVER, &nrf_rx); + +// Every 200 miliseconds +Task task_web(200, TASK_FOREVER, &web_handler); +Task task_ota(200, TASK_FOREVER, &ota_handler); + +// Every 0.5 seconds +Task task_heartbeat(500, TASK_FOREVER, &status_heartbeat); + +// Every second +Task task_uptime(1000, TASK_FOREVER, &uptime_tracker); + +void setup() { + Serial.begin(115200); + + // Delay a bit + delay(100); + + // Setting up status led + pinMode(LED_STATUS, OUTPUT); + pinMode(LED_HEARTBEAT, OUTPUT); + + // Starting up storage + storage.begin(); + + // Starting up SBUS + sbus.begin(); + + // One wire as SBUS (TX) + // Serial2.begin(100000, SERIAL_8E2); + // swSer1.begin(100000, SWSERIAL_8N2, D5, D5, false, 256); + + // Start up NRF24L01 + //////// rx.begin(); + + // Setup Receiver + // setup_rx(); + + // For OTA + customwifi.begin(); + ota.begin(); + web.begin(); + + scheduler.init(); + + Serial.println("Enabling Tasks..."); + // Add task to scheduler + scheduler.addTask(task_sbus_generator); + ////////// scheduler.addTask(task_rx); + scheduler.addTask(task_heartbeat); + scheduler.addTask(task_web); + scheduler.addTask(task_ota); + scheduler.addTask(task_uptime); + + // Enabling Tasks + task_sbus_generator.enable(); + //////////// task_rx.enable(); + task_heartbeat.enable(); + task_web.enable(); + task_ota.enable(); + task_uptime.enable(); + + + Serial.println("SimpleRX OK"); +} + +void loop() { + scheduler.execute(); +} + +void web_handler(void) { + web.handler(); +} + +void ota_handler(void) { + ota.run(); +} + + +uint32_t gpio_count = 0; +uint32_t profile_start = 0; + +void status_heartbeat(void) { + led_heartbeat_state = !led_heartbeat_state; + if(led_heartbeat_state) { + GPOS = (1 << LED_HEARTBEAT); + GPOS = (1 << LED_STATUS); + } else { + GPOC = (1 << LED_HEARTBEAT); + GPOC = (1 << LED_STATUS); + } + + /***** + gpio_count = 0; + profile_start = millis(); + + while((uint32_t)(millis() - profile_start) < 1000) { + GPOS = (1 << LED_STATUS); + GPOC = (1 << LED_STATUS); + gpio_count++; + } + + Serial.println(gpio_count); + ****/ +} + +// Keep sending SBUS +void send_sbus(void) { + sbus.writePackets(); +} + + +uint32_t uptime_total = 0; +void uptime_tracker(void) { + uptime_total++; +} + + +// DEBUGGING... +uint32_t printagain = 0; +bool first_load = true; +// Processing received data +void nrf_rx(void) { + if(first_load == true) { + if(uptime_total < 5) { + // Do nothing till it stablized... + return; + } + + // Next loop wont be here.... + first_load = false; + + setup_rx(); + Serial.println("NRF READY TO LISTEN..."); + } + + if(rx.available()) { + // Getting signals from Receiver + rx.read(&rxMessage, sizeof(RXMessage)); + + // Debugging only. Remove this once working. + Serial.print(rxMessage.Byte00); + Serial.print(" "); + Serial.print(rxMessage.Byte01); + Serial.print(" "); + Serial.print(rxMessage.Byte02); + Serial.print(" "); + Serial.print(rxMessage.Byte03); + Serial.print(" "); + Serial.print(rxMessage.Byte04); + Serial.print(" "); + Serial.print(rxMessage.Byte05); + Serial.println(" "); + + // static bool firstload = true; + + // 2021 New Data format for saving 2 bytes: + // 1234 5678 9TTT TTTT TTTT -YYY YYYY YYYY -PPP PPPP PPPP -RRR RRRR RRRR (7 Bytes) + // |-------| |-------| |-------| |-------| |-------| |-------| |-------| + // Byte 00 Byte 01 Byte 02 Byte 03 Byte 04 Byte 05 Byte 06 + + // Extracting data + // Processing switches channel.... + /**** + rcCommand[AUX1] = ((rxMessage.Byte00 >> 7) & 0x01) ? 2000 : 1000; // 1 + rcCommand[AUX2] = ((rxMessage.Byte00 >> 6) & 0x01) ? 2000 : 1000; // 2 + rcCommand[AUX3] = ((rxMessage.Byte00 >> 5) & 0x01) ? 2000 : 1000; // 3 + rcCommand[AUX4] = ((rxMessage.Byte00 >> 4) & 0x01) ? 2000 : 1000; // 4 + rcCommand[AUX5] = ((rxMessage.Byte00 >> 3) & 0x01) ? 2000 : 1000; // 5 + rcCommand[AUX6] = ((rxMessage.Byte00 >> 2) & 0x01) ? 2000 : 1000; // 6 + rcCommand[AUX7] = ((rxMessage.Byte00 >> 1) & 0x01) ? 2000 : 1000; // 7 + rcCommand[AUX8] = ((rxMessage.Byte00 >> 0) & 0x01) ? 2000 : 1000; // 8 + rcCommand[AUX9] = ((rxMessage.Byte01 >> 7) & 0x01) ? 2000 : 1000; // 9 + ***/ + rcCommand[AUX1] = ((rxMessage.Byte00 >> 7) & 0x01) ? 1 : 0; // 1 + rcCommand[AUX2] = ((rxMessage.Byte00 >> 6) & 0x01) ? 1 : 0; // 2 + rcCommand[AUX3] = ((rxMessage.Byte00 >> 5) & 0x01) ? 1 : 0; // 3 + rcCommand[AUX4] = ((rxMessage.Byte00 >> 4) & 0x01) ? 1 : 0; // 4 + rcCommand[AUX5] = ((rxMessage.Byte00 >> 3) & 0x01) ? 1 : 0; // 5 + rcCommand[AUX6] = ((rxMessage.Byte00 >> 2) & 0x01) ? 1 : 0; // 6 + rcCommand[AUX7] = ((rxMessage.Byte00 >> 1) & 0x01) ? 1 : 0; // 7 + rcCommand[AUX8] = ((rxMessage.Byte00 >> 0) & 0x01) ? 1 : 0; // 8 + rcCommand[AUX9] = ((rxMessage.Byte01 >> 7) & 0x01) ? 1 : 0; // 9 + + rcCommand[THROTTLE] = ((rxMessage.Byte01 & 0X7F) << 4) | (rxMessage.Byte02 & 0xF0) >> 4; // Throttle + rcCommand[YAW] = ((rxMessage.Byte02 & 0x07) << 8) | rxMessage.Byte03; // Yaw + rcCommand[PITCH] = ((rxMessage.Byte04 & 0x7F) << 4) | (rxMessage.Byte05 & 0xF0) >> 4; // Pitch + rcCommand[ROLL] = ((rxMessage.Byte05 & 0x07) << 8) | rxMessage.Byte06; // Roll + + } +} + +void setup_rx(void) { + rx.stopListening(); + rx.setAutoAck(false); + rx.setChannel(0x08); // Temporary at 8 Later read from LittleFS + rx.setPayloadSize(sizeof(RXMessage)); + rx.setDataRate(RF24_250KBPS); + rx.setPALevel(RF24_PA_MAX); + rx.openReadingPipe(1, pipeIn); + rx.startListening(); +} diff --git a/src/main.h b/src/main.h new file mode 100644 index 0000000..baca640 --- /dev/null +++ b/src/main.h @@ -0,0 +1,34 @@ +#ifndef MAIN_H +#define MAIN_H + +// For NRF24L01P +#define MAX_CHANNELS 125 +#define RX_CE_PIN 5 +#define RX_CSN_PIN 4 +#define _SPI SPI + +const uint64_t pipeIn = 0xE8E8F0F0E1LL; // Must be same as the transmission + +// Enable type of microcontroller for the nrf24l01 library to compile. +// #define ESP32 +#define ESP12E + +#include "nrf24l01.h" +#include "CustomWiFi.h" +#include "OTA.h" +#include "sbus.h" +#include "Storage.h" +#include "Web.h" + +void send_sbus(void); +void setup_nrf_rx(void); +void setup_rx(void); +void nrf_rx(void); +void sbusPreparePacket(uint8_t packet[], int channels[], bool isSignalLoss, bool isFailsafe); +void status_heartbeat(void); +void web_handler(void); +void ota_handler(void); +void uptime_tracker(void); + + +#endif diff --git a/src/nrf24l01.cpp b/src/nrf24l01.cpp new file mode 100644 index 0000000..846964f --- /dev/null +++ b/src/nrf24l01.cpp @@ -0,0 +1,1318 @@ +/* + * Filename: nrf24l01.cpp + * Date: Sat 13 Nov 19:33:42 +08 2021 + * Author: Englebert + * Description: + * This is a re-write nRF24L01 driver for ESP32. It will use the fastest way to + * communicate. It utilized the DMA way to maximized the data transfer rate. + * + * Copyright (C) + * 2011 J. Coliz + * 2015-2019 TMRh20 + * 2015 spaniakos + * 2015 nerdralph + * 2015 zador-blood-stained + * 2016 akatran + * 2017-2019 Avamander + * 2019 IkpeohaGodson + * 2021 Englebert + * + * 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. + */ +#include "nrf24l01.h" + +// Use uniform initializer syntax +NRF24L01::NRF24L01(uint16_t _cepin, uint16_t _cspin, uint32_t _spi_speed):ce_pin(_cepin),csn_pin(_cspin),spi_speed(_spi_speed),payload_size(32),dynamic_payloads_enabled(false),addr_width(5),csDelay(5) { + //,pipe0_reading_address(0) + pipe0_reading_address[0] = 0; + spi_speed = RF24_SPI_SPEED; + + // set to high first for others to initialize + csn(HIGH); +} + + +inline void NRF24L01::beginTransaction() { + _SPI.beginTransaction(SPISettings(spi_speed, MSBFIRST, SPI_MODE0)); + csn(LOW); +} + + +inline void NRF24L01::endTransaction() { + csn(HIGH); + _SPI.endTransaction(); +} + + +/* + * Set chip select pin + * @param mode HIGH to take this unit off the SPI bus, LOW to put it on + */ +void NRF24L01::csn(bool mode) { + if(mode == HIGH) { + #if defined(ESP32) + GPIO.out_w1ts = ((uint32_t)1 << csn_pin); // CSN HIGH + #elif defined(ESP12E) + GPOS = (1 << csn_pin); // CSN HIGH + #else + #error "PLEASE DEFINE A MICROCONTROLLER" + #endif + delayMicroseconds(100); // Allow CSN to settle. + } else { + #if defined(ESP32) + GPIO.out_w1tc = ((uint32_t)1 << csn_pin); // CSN LOW + #elif defined(ESP12E) + GPOC = (1 << csn_pin); // CSN LOW + #else + #error "PLEASE DEFINE A MICROCONTROLLER" + #endif + delayMicroseconds(11); // Allow CSN to settle. + } +} + + +/* + * Set chip enable + * + * @param level HIGH to actively begin transmission or LOW to put in standby. + */ +void NRF24L01::ce(bool level) { + // Allow for 3-pins use + if(ce_pin != csn_pin) { + if(level == HIGH) { + #if defined(ESP32) + GPIO.out_w1ts = ((uint32_t)1 << ce_pin); // CE HIGH + #elif defined(ESP12E) + GPOS = (1 << ce_pin); // CE HIGH + #else + #error "PLEASE DEFINE A MICROCONTROLLER" + #endif + } else { + #if defined(ESP32) + GPIO.out_w1tc = ((uint32_t)1 << ce_pin); // CE LOW + #elif defined(ESP12E) + GPOC = (1 << ce_pin); // CE LOW + #else + #error "PLEASE DEFINE A MICROCONTROLLER" + #endif + } + } +} + + +/* + * Read a chunk of data in from a register + * + * @param reg Which register. Use constants from nRF24L01.h + * @param buf Where to put the data + * @param len How many bytes of data to transfer + * @return Current value of status register + */ +uint8_t NRF24L01::read_register(uint8_t reg, uint8_t* buf, uint8_t len) { + uint8_t status; + + beginTransaction(); + status = _SPI.transfer(R_REGISTER | (REGISTER_MASK & reg)); + while(len--) { + *buf++ = _SPI.transfer(0xff); + } + endTransaction(); + + return status; +} + + +/* + * Read single byte from a register + * + * @param reg Which register. Use constants from nRF24L01.h + * @return Current value of register @p reg + */ +uint8_t NRF24L01::read_register(uint8_t reg) { + uint8_t result; + + beginTransaction(); + _SPI.transfer(R_REGISTER | (REGISTER_MASK & reg)); + result = _SPI.transfer(0xff); + endTransaction(); + + return result; +} + + +/* + * Write a chunk of data to a register + * + * @param reg Which register. Use constants from nRF24L01.h + * @param buf Where to get the data + * @param len How many bytes of data to transfer + * @return Current value of status register + */ +uint8_t NRF24L01::write_register(uint8_t reg, const uint8_t* buf, uint8_t len) { + uint8_t status; + + beginTransaction(); + status = _SPI.transfer(W_REGISTER | (REGISTER_MASK & reg)); + while(len--) { + _SPI.transfer(*buf++); + } + endTransaction(); + + return status; +} + + +/* + * Write a single byte to a register + * + * @param reg Which register. Use constants from nRF24L01.h + * @param value The new value to write + * @return Current value of status register + */ +uint8_t NRF24L01::write_register(uint8_t reg, uint8_t value) { + uint8_t status; + + // IF_SERIAL_DEBUG(printf_P(PSTR("write_register(%02x,%02x)\r\n"), reg, value)); + beginTransaction(); + status = _SPI.transfer(W_REGISTER | (REGISTER_MASK & reg)); + _SPI.transfer(value); + endTransaction(); + + return status; +} + + +/* + * Write the transmit payload + * + * The size of data written is the fixed payload size, see getPayloadSize() + * + * @param buf Where to get the data + * @param len Number of bytes to be sent + * @return Current value of status register + */ +uint8_t NRF24L01::write_payload(const void* buf, uint8_t data_len, const uint8_t writeType) { + uint8_t status; + const uint8_t* current = reinterpret_cast(buf); + + data_len = rf24_min(data_len, payload_size); + uint8_t blank_len = dynamic_payloads_enabled ? 0 : payload_size - data_len; + + //printf("[Writing %u bytes %u blanks]",data_len,blank_len); + // IF_SERIAL_DEBUG(printf("[Writing %u bytes %u blanks]\n", data_len, blank_len); ); + + beginTransaction(); + status = _SPI.transfer(writeType); + while(data_len--) { + _SPI.transfer(*current++); + } + while (blank_len--) { + _SPI.transfer(0); + } + endTransaction(); + + return status; +} + + +/* + * Read the receive payload + * + * The size of data read is the fixed payload size, see getPayloadSize() + * + * @param buf Where to put the data + * @param len Maximum number of bytes to read + * @return Current value of status register + */ +uint8_t NRF24L01::read_payload(void* buf, uint8_t data_len) { + uint8_t status; + uint8_t* current = reinterpret_cast(buf); + + if(data_len > payload_size) { + data_len = payload_size; + } + uint8_t blank_len = dynamic_payloads_enabled ? 0 : payload_size - data_len; + + // printf("[Reading %u bytes %u blanks]",data_len,blank_len); + // IF_SERIAL_DEBUG(printf("[Reading %u bytes %u blanks]\n", data_len, blank_len); ); + + beginTransaction(); + status = _SPI.transfer(R_RX_PAYLOAD); + while(data_len--) { + *current++ = _SPI.transfer(0xFF); + } + while(blank_len--) { + _SPI.transfer(0xff); + } + endTransaction(); + + return status; +} + + +/* + * Empty the receive buffer + * + * @return Current value of status register + */ +uint8_t NRF24L01::flush_rx(void) { + return spiTrans(FLUSH_RX); +} + + +/* + * Empty the transmit buffer. This is generally not required in standard operation. + * May be required in specific cases after stopListening() , if operating at 250KBPS data rate. + * + * @return Current value of status register + */ +uint8_t NRF24L01::flush_tx(void) { + return spiTrans(FLUSH_TX); +} + + +/* + * Built in spi transfer function to simplify repeating code repeating code + */ +uint8_t NRF24L01::spiTrans(uint8_t cmd) { + + uint8_t status; + + beginTransaction(); + status = _SPI.transfer(cmd); + endTransaction(); + + return status; +} + + +/* + * Retrieve the current status of the chip + * @return Current value of status register + */ +uint8_t NRF24L01::get_status(void) { + return spiTrans(RF24_NOP); +} + + +/** + * Set RF communication channel + * + * @param channel Which RF channel to communicate on, 0-125 + */ +void NRF24L01::setChannel(uint8_t channel) { + const uint8_t max_channel = 125; + write_register(RF_CH, rf24_min(channel, max_channel)); +} + + +/* + * Get RF communication channel + * + * @return The currently configured RF Channel + */ +uint8_t NRF24L01::getChannel() { + return read_register(RF_CH); +} + + +/* + * Set Static Payload Size + * + * This implementation uses a pre-stablished fixed payload size for all + * transmissions. If this method is never called, the driver will always + * transmit the maximum payload size (32 bytes), no matter how much + * was sent to write(). + * + * @todo Implement variable-sized payloads feature + * + * @param size The number of bytes in the payload + */ +void NRF24L01::setPayloadSize(uint8_t size) { + payload_size = rf24_min(size, 32); +} + + +/* + * Get Static Payload Size + * + * @see setPayloadSize() + * @return The number of bytes in the payload + */ +uint8_t NRF24L01::getPayloadSize(void) { + return payload_size; +} + + +static const PROGMEM char rf24_datarate_e_str_0[] = "1MBPS"; +static const PROGMEM char rf24_datarate_e_str_1[] = "2MBPS"; +static const PROGMEM char rf24_datarate_e_str_2[] = "250KBPS"; +static const PROGMEM char * const rf24_datarate_e_str_P[] = { + rf24_datarate_e_str_0, + rf24_datarate_e_str_1, + rf24_datarate_e_str_2, +}; +static const PROGMEM char rf24_model_e_str_0[] = "nRF24L01"; +static const PROGMEM char rf24_model_e_str_1[] = "nRF24L01+"; +static const PROGMEM char * const rf24_model_e_str_P[] = { + rf24_model_e_str_0, + rf24_model_e_str_1, +}; +static const PROGMEM char rf24_crclength_e_str_0[] = "Disabled"; +static const PROGMEM char rf24_crclength_e_str_1[] = "8 bits"; +static const PROGMEM char rf24_crclength_e_str_2[] = "16 bits" ; +static const PROGMEM char * const rf24_crclength_e_str_P[] = { + rf24_crclength_e_str_0, + rf24_crclength_e_str_1, + rf24_crclength_e_str_2, +}; +static const PROGMEM char rf24_pa_dbm_e_str_0[] = "PA_MIN"; +static const PROGMEM char rf24_pa_dbm_e_str_1[] = "PA_LOW"; +static const PROGMEM char rf24_pa_dbm_e_str_2[] = "PA_HIGH"; +static const PROGMEM char rf24_pa_dbm_e_str_3[] = "PA_MAX"; +static const PROGMEM char * const rf24_pa_dbm_e_str_P[] = { + rf24_pa_dbm_e_str_0, + rf24_pa_dbm_e_str_1, + rf24_pa_dbm_e_str_2, + rf24_pa_dbm_e_str_3, +}; +static const PROGMEM uint8_t child_pipe_enable[] = {ERX_P0, ERX_P1, ERX_P2, + ERX_P3, ERX_P4, ERX_P5}; + + +/* + * Print a giant block of debugging information to stdout + * + * @warning Does nothing if stdout is not defined. See fdevopen in stdio.h + * The printf.h file is included with the library for Arduino. + * @code + * #include + * setup(){ + * Serial.begin(115200); + * printf_begin(); + * ... + * } + * @endcode + */ +void NRF24L01::printDetails(void) { + + printf_P(PSTR("SPI Speedz\t = %d Mhz\n"),(uint8_t)(spi_speed/1000000)); //Print the SPI speed on non-Linux devices + print_status(get_status()); + + print_address_register(PSTR("RX_ADDR_P0-1"), RX_ADDR_P0, 2); + print_byte_register(PSTR("RX_ADDR_P2-5"), RX_ADDR_P2, 4); + print_address_register(PSTR("TX_ADDR\t"), TX_ADDR); + + print_byte_register(PSTR("RX_PW_P0-6"), RX_PW_P0, 6); + print_byte_register(PSTR("EN_AA\t"), EN_AA); + print_byte_register(PSTR("EN_RXADDR"), EN_RXADDR); + print_byte_register(PSTR("RF_CH\t"), RF_CH); + print_byte_register(PSTR("RF_SETUP"), RF_SETUP); + print_byte_register(PSTR("CONFIG\t"), NRF_CONFIG); + print_byte_register(PSTR("DYNPD/FEATURE"), DYNPD, 2); + + printf_P(PSTR("Data Rate\t = " + PRIPSTR + "\r\n"),(char*)pgm_read_ptr(&rf24_datarate_e_str_P[getDataRate()])); + printf_P(PSTR("Model\t\t = " + PRIPSTR + "\r\n"),(char*)pgm_read_ptr(&rf24_model_e_str_P[isPVariant()])); + printf_P(PSTR("CRC Length\t = " + PRIPSTR + "\r\n"),(char*)pgm_read_ptr(&rf24_crclength_e_str_P[getCRCLength()])); + printf_P(PSTR("PA Power\t = " + PRIPSTR + "\r\n"),(char*)pgm_read_ptr(&rf24_pa_dbm_e_str_P[getPALevel()])); + printf_P(PSTR("ARC\t\t = %d\r\n"), getARC()); +} + + +/** + * Begin operation of the chip + * + * Call this in setup(), before calling any other methods. + * @code radio.begin() @endcode + */ +bool NRF24L01::begin(void) { + // Initialize pins + if(ce_pin != csn_pin) { + pinMode(ce_pin, OUTPUT); + pinMode(csn_pin, OUTPUT); + } + // _SPI.begin(); + ce(LOW); + csn(HIGH); + + // Must allow the radio time to settle else configuration bits will not necessarily stick. + // This is actually only required following power up but some settling time also appears to + // be required after resets too. For full coverage, we'll always assume the worst. + // Enabling 16b CRC is by far the most obvious case if the wrong timing is used - or skipped. + // Technically we require 4.5ms + 14us as a worst case. We'll just call it 5ms for good measure. + // WARNING: Delay is based on P-variant whereby non-P *may* require different timing. + // delay(5); + #if defined(ESP32) + vTaskDelay(5 / portTICK_PERIOD_MS); + #elif defined(ESP12E) + delay(5); + #else + #error "PLEASE DEFINE A MICROCONTROLLER" + #endif + + // Set 1500uS (minimum for 32B payload in ESB@250KBPS) timeouts, to make testing a little easier + // WARNING: If this is ever lowered, either 250KBS mode with AA is broken or maximum packet + // sizes must never be used. See documentation for a more complete explanation. + setRetries(5, 15); + + // Then set the data rate to the slowest (and most reliable) speed supported by all + // hardware. + setDataRate(RF24_1MBPS); + + // Disable dynamic payloads, to match dynamic_payloads_enabled setting - Reset value is 0 + toggle_features(); + write_register(FEATURE, 0); + write_register(DYNPD, 0); + dynamic_payloads_enabled = false; + ack_payloads_enabled = false; + + // Reset current status + // Notice reset and flush is the last thing we do + write_register(NRF_STATUS, _BV(RX_DR) | _BV(TX_DS) | _BV(MAX_RT)); + + // Set up default configuration. Callers can always change it later. + // This channel should be universally safe and not bleed over into adjacent + // spectrum. + setChannel(76); + + // Flush buffers + flush_rx(); + flush_tx(); + + // Clear CONFIG register, Enable PTX, Power Up & 16-bit CRC + // Do not write CE high so radio will remain in standby I mode + // PTX should use only 22uA of power + write_register(NRF_CONFIG, (_BV(EN_CRC) | _BV(CRCO)) ); + config_reg = read_register(NRF_CONFIG); + + powerUp(); + + // if config is not set correctly then there was a bad response from module + return config_reg == (_BV(EN_CRC) | _BV(CRCO) | _BV(PWR_UP)) ? true : false; +} + + +/** + * Checks if the chip is connected to the SPI bus + */ +bool NRF24L01::isChipConnected() { + uint8_t setup = read_register(SETUP_AW); + if(setup >= 1 && setup <= 3) { + return true; + } + + return false; +} + + +/* + * Start listening on the pipes opened for reading. + * + * 1. Be sure to call openReadingPipe() first. + * 2. Do not call write() while in this mode, without first calling stopListening(). + * 3. Call available() to check for incoming traffic, and read() to get it. + * + * @code + * Open reading pipe 1 using address CCCECCCECC + * + * byte address[] = { 0xCC,0xCE,0xCC,0xCE,0xCC }; + * radio.openReadingPipe(1,address); + * radio.startListening(); + * @endcode + */ +void NRF24L01::startListening(void) { + powerUp(); + + /* Notes Once ready for next release + * 1. Can update stopListening() to use config_reg var and ack_payloads_enabled var instead of SPI rx/tx + * 2. Update txDelay defaults: 240 for 2MBPS, 280 for 1MBPS, 505 for 250KBPS per initial testing + * 3. Allows time for slower devices to update with the faster startListening() function prior to updating stopListening() & adjusting txDelay + */ + config_reg |= _BV(PRIM_RX); + write_register(NRF_CONFIG,config_reg); + write_register(NRF_STATUS, _BV(RX_DR) | _BV(TX_DS) | _BV(MAX_RT)); + ce(HIGH); + + // Restore the pipe0 adddress, if exists + if(pipe0_reading_address[0] > 0) { + write_register(RX_ADDR_P0, pipe0_reading_address, addr_width); + } else { + closeReadingPipe(0); + } + + if(ack_payloads_enabled) { + flush_tx(); + } +} + + +/* + * Stop listening for incoming messages, and switch to transmit mode. + * + * Do this before calling write(). + * @code + * radio.stopListening(); + * radio.write(&data,sizeof(data)); + * @endcode + */ +void NRF24L01::stopListening(void) { + ce(LOW); + + delayMicroseconds(txDelay); + + if(read_register(FEATURE) & _BV(EN_ACK_PAY)) { + delayMicroseconds(txDelay); //200 + flush_tx(); + } + //flush_rx(); + config_reg &= ~_BV(PRIM_RX); + write_register(NRF_CONFIG,config_reg); + + // for 3 pins solution TX mode is only left with additonal powerDown/powerUp cycle + if(ce_pin == csn_pin) { + powerDown(); + powerUp(); + } + + // Enable RX on pipe0 + write_register(EN_RXADDR, read_register(EN_RXADDR) | _BV(pgm_read_byte(&child_pipe_enable[0]))); + //delayMicroseconds(100); +} + + +/** + * Enter low-power mode + * + * To return to normal power mode, call powerUp(). + * + * @note After calling startListening(), a basic radio will consume about 13.5mA + * at max PA level. + * During active transmission, the radio will consume about 11.5mA, but this will + * be reduced to 26uA (.026mA) between sending. + * In full powerDown mode, the radio will consume approximately 900nA (.0009mA) + * + * @code + * radio.powerDown(); + * avr_enter_sleep_mode(); // Custom function to sleep the device + * radio.powerUp(); + * @endcode + */ +void NRF24L01::powerDown(void) { + ce(LOW); // Guarantee CE is low on powerDown + config_reg &= ~_BV(PWR_UP); + write_register(NRF_CONFIG,config_reg); +} + + +/* + * Leave low-power mode - required for normal radio operation after calling powerDown() + * + * To return to low power mode, call powerDown(). + * @note This will take up to 5ms for maximum compatibility + */ +// Power up now. Radio will not power down unless instructed by MCU for config changes etc. +void NRF24L01::powerUp(void) { + // if not powered up then power up and wait for the radio to initialize + if (!(config_reg & _BV(PWR_UP))) { + config_reg |= _BV(PWR_UP); + write_register(NRF_CONFIG, config_reg); + + // For nRF24L01+ to go from power down mode to TX or RX mode it must first pass through stand-by mode. + // There must be a delay of Tpd2stby (see Table 16.) after the nRF24L01+ leaves power down mode before + // the CEis set high. - Tpd2stby can be up to 5ms per the 1.0 datasheet + // delay(5); + #if defined(ESP32) + vTaskDelay(5 / portTICK_PERIOD_MS); + #elif defined(ESP12E) + delay(5); + #else + #error "PLEASE DEFINE A MICROCONTROLLER" + #endif + } +} + +void NRF24L01::errNotify() { + // #if defined(SERIAL_DEBUG) || defined(RF24_LINUX) + // printf_P(PSTR("RF24 HARDWARE FAIL: Radio not responding, verify pin connections, wiring, etc.\r\n")); + // #endif + // #if defined(FAILURE_HANDLING) + failureDetected = 1; + // #else + // delay(5000); + // #endif +} + + +/* + * Write for single NOACK writes. Optionally disables acknowledgements/autoretries for a single write. + * + * @note enableDynamicAck() must be called to enable this feature + * + * Can be used with enableAckPayload() to request a response + * @see enableDynamicAck() + * @see setAutoAck() + * @see write() + * + * @param buf Pointer to the data to be sent + * @param len Number of bytes to be sent + * @param multicast Request ACK (0), NOACK (1) + */ +// Similar to the previous write, clears the interrupt flags +bool NRF24L01::write(const void* buf, uint8_t len, const bool multicast) { + // Start Writing + startFastWrite(buf, len, multicast); + + // Wait until complete or failed + uint32_t timer = millis(); + + while (!(get_status() & (_BV(TX_DS) | _BV(MAX_RT)))) { + if (millis() - timer > 95) { + errNotify(); + return 0; + } + } + + ce(LOW); + + uint8_t status = write_register(NRF_STATUS, _BV(RX_DR) | _BV(TX_DS) | _BV(MAX_RT)); + + // Max retries exceeded + if(status & _BV(MAX_RT)) { + flush_tx(); //Only going to be 1 packet int the FIFO at a time using this method, so just flush + return 0; + } + + //TX OK 1 or 0 + return 1; +} + +bool NRF24L01::write(const void* buf, uint8_t len) { + return write(buf, len, 0); +} + +//For general use, the interrupt flags are not important to clear +bool NRF24L01::writeBlocking(const void* buf, uint8_t len, uint32_t timeout) { + // Block until the FIFO is NOT full. + // Keep track of the MAX retries and set auto-retry if seeing failures + // This way the FIFO will fill up and allow blocking until packets go through + // The radio will auto-clear everything in the FIFO as long as CE remains high + + uint32_t timer = millis(); // Get the time that the payload transmission started + + while( + ( + get_status() & + (_BV(TX_FULL)) + ) + ) { + // Blocking only if FIFO is full. This will loop and block until TX is successful or timeout + if(get_status() & _BV(MAX_RT)) { // If MAX Retries have been reached + reUseTX(); // Set re-transmit and clear the MAX_RT interrupt flag + if(millis() - timer > timeout) { + return 0; + } // If this payload has exceeded the user-defined timeout, exit and return 0 + } + + if (millis() - timer > (timeout + 95)) { + errNotify(); + return 0; + } + } + + //Start Writing + startFastWrite(buf, len, 0); // Write the payload if a buffer is clear + + return 1; // Return 1 to indicate successful transmission +} + +void NRF24L01::reUseTX() { + write_register(NRF_STATUS, _BV(MAX_RT)); // Clear max retry flag + spiTrans(REUSE_TX_PL); + ce(LOW); // Re-Transfer packet + ce(HIGH); +} + + +bool NRF24L01::writeFast(const void* buf, uint8_t len, const bool multicast) { + // Block until the FIFO is NOT full. + // Keep track of the MAX retries and set auto-retry if seeing failures + // Return 0 so the user can control the retrys and set a timer or failure counter if required + // The radio will auto-clear everything in the FIFO as long as CE remains high + + uint32_t timer = millis(); + + // Blocking only if FIFO is full. This will loop and block until TX is successful or fail + while((get_status() & (_BV(TX_FULL)))) { + if(get_status() & _BV(MAX_RT)) { + return 0; // Return 0. The previous payload has been retransmitted + // From the user perspective, if you get a 0, just keep trying to send the same payload + } + if(millis() - timer > 95) { + errNotify(); + return 0; + } + } + // Start Writing + startFastWrite(buf, len, multicast); + return 1; +} + +bool NRF24L01::writeFast(const void* buf, uint8_t len) { + return writeFast(buf, len, 0); +} + + +// Per the documentation, we want to set PTX Mode when not listening. Then all we do is write data and set CE high +// In this mode, if we can keep the FIFO buffers loaded, packets will transmit immediately (no 130us delay) +// Otherwise we enter Standby-II mode, which is still faster than standby mode +// Also, we remove the need to keep writing the config register over and over and delaying for 150 us each time if sending a stream of data + +void NRF24L01::startFastWrite(const void* buf, uint8_t len, const bool multicast, bool startTx) { + //TMRh20 + //write_payload( buf,len); + write_payload(buf, len, multicast ? W_TX_PAYLOAD_NO_ACK : W_TX_PAYLOAD); + if(startTx) { + ce(HIGH); + } +} + + +// Added the original startWrite back in so users can still use interrupts, ack payloads, etc +// Allows the library to pass all tests +void NRF24L01::startWrite(const void* buf, uint8_t len, const bool multicast) { + // Send the payload + // write_payload( buf, len ); + write_payload(buf, len, multicast ? W_TX_PAYLOAD_NO_ACK : W_TX_PAYLOAD); + ce(HIGH); + delayMicroseconds(10); + ce(LOW); +} + + +bool NRF24L01::rxFifoFull() { + return read_register(FIFO_STATUS) & _BV(RX_FULL); +} + + +bool NRF24L01::txStandBy() { + uint32_t timeout = millis(); + while(!(read_register(FIFO_STATUS) & _BV(TX_EMPTY))) { + if(get_status() & _BV(MAX_RT)) { + write_register(NRF_STATUS, _BV(MAX_RT)); + ce(LOW); + flush_tx(); // Non blocking, flush the data + return 0; + } + if(millis() - timeout > 95) { + errNotify(); + return 0; + } + } + + ce(LOW); // Set STANDBY-I mode + return 1; +} + + +bool NRF24L01::txStandBy(uint32_t timeout, bool startTx) { + if(startTx) { + stopListening(); + ce(HIGH); + } + uint32_t start = millis(); + + while(!(read_register(FIFO_STATUS) & _BV(TX_EMPTY))) { + if(get_status() & _BV(MAX_RT)) { + write_register(NRF_STATUS, _BV(MAX_RT)); + ce(LOW); // Set re-transmit + ce(HIGH); + if(millis() - start >= timeout) { + ce(LOW); + flush_tx(); + return 0; + } + } + if(millis() - start > (timeout + 95)) { + errNotify(); + return 0; + } + } + + ce(LOW); // Set STANDBY-I mode + return 1; + +} + + +void NRF24L01::maskIRQ(bool tx, bool fail, bool rx) { + /* clear the interrupt flags */ + config_reg &= ~(1 << MASK_MAX_RT | 1 << MASK_TX_DS | 1 << MASK_RX_DR); + /* set the specified interrupt flags */ + config_reg |= fail << MASK_MAX_RT | tx << MASK_TX_DS | rx << MASK_RX_DR; + write_register(NRF_CONFIG, config_reg); +} + + +uint8_t NRF24L01::getDynamicPayloadSize(void) { + uint8_t result = 0; + + #if defined(RF24_LINUX) + spi_txbuff[0] = R_RX_PL_WID; + spi_txbuff[1] = 0xff; + beginTransaction(); + _SPI.transfernb( (char *) spi_txbuff, (char *) spi_rxbuff, 2); + result = spi_rxbuff[1]; + endTransaction(); + #else + beginTransaction(); + _SPI.transfer(R_RX_PL_WID); + result = _SPI.transfer(0xff); + endTransaction(); + #endif + + if (result > 32) { + flush_rx(); + delay(2); + return 0; + } + return result; +} + + +bool NRF24L01::available(void) { + return available(NULL); +} + + +bool NRF24L01::available(uint8_t* pipe_num) { + // get implied RX FIFO empty flag from status byte + uint8_t pipe = (get_status() >> RX_P_NO) & 0x07; + if (pipe > 5) + return 0; + + // If the caller wants the pipe number, include that + if (pipe_num) + *pipe_num = pipe; + + return 1; +} + + +void NRF24L01::read(void* buf, uint8_t len) { + + // Fetch the payload + read_payload(buf, len); + + //Clear the two possible interrupt flags with one command + write_register(NRF_STATUS, _BV(RX_DR) | _BV(MAX_RT) | _BV(TX_DS)); + +} + + +void NRF24L01::whatHappened(bool& tx_ok, bool& tx_fail, bool& rx_ready) { + // Read the status & reset the status in one easy call + // Or is that such a good idea? + uint8_t status = write_register(NRF_STATUS, _BV(RX_DR) | _BV(TX_DS) | _BV(MAX_RT)); + + // Report to the user what happened + tx_ok = status & _BV(TX_DS); + tx_fail = status & _BV(MAX_RT); + rx_ready = status & _BV(RX_DR); +} + + +void NRF24L01::openWritingPipe(uint64_t value) { + // Note that AVR 8-bit uC's store this LSB first, and the NRF24L01(+) + // expects it LSB first too, so we're good. + + write_register(RX_ADDR_P0, reinterpret_cast(&value), addr_width); + write_register(TX_ADDR, reinterpret_cast(&value), addr_width); + + + //const uint8_t max_payload_size = 32; + //write_register(RX_PW_P0,rf24_min(payload_size,max_payload_size)); + write_register(RX_PW_P0, payload_size); +} + + +void NRF24L01::openWritingPipe(const uint8_t* address) { + // Note that AVR 8-bit uC's store this LSB first, and the NRF24L01(+) + // expects it LSB first too, so we're good. + write_register(RX_ADDR_P0, address, addr_width); + write_register(TX_ADDR, address, addr_width); + + //const uint8_t max_payload_size = 32; + //write_register(RX_PW_P0,rf24_min(payload_size,max_payload_size)); + write_register(RX_PW_P0, payload_size); +} + +static const PROGMEM uint8_t child_pipe[] = {RX_ADDR_P0, RX_ADDR_P1, RX_ADDR_P2, + RX_ADDR_P3, RX_ADDR_P4, RX_ADDR_P5}; +static const PROGMEM uint8_t child_payload_size[] = {RX_PW_P0, RX_PW_P1, RX_PW_P2, + RX_PW_P3, RX_PW_P4, RX_PW_P5}; + +void NRF24L01::openReadingPipe(uint8_t child, uint64_t address) { + // If this is pipe 0, cache the address. This is needed because + // openWritingPipe() will overwrite the pipe 0 address, so + // startListening() will have to restore it. + if (child == 0) { + memcpy(pipe0_reading_address, &address, addr_width); + } + + if (child <= 5) { + // For pipes 2-5, only write the LSB + if (child < 2) { + write_register(pgm_read_byte(&child_pipe[child]), reinterpret_cast(&address), addr_width); + } else { + write_register(pgm_read_byte(&child_pipe[child]), reinterpret_cast(&address), 1); + } + + write_register(pgm_read_byte(&child_payload_size[child]), payload_size); + + // Note it would be more efficient to set all of the bits for all open + // pipes at once. However, I thought it would make the calling code + // more simple to do it this way. + write_register(EN_RXADDR, read_register(EN_RXADDR) | _BV(pgm_read_byte(&child_pipe_enable[child]))); + } +} + + +void NRF24L01::setAddressWidth(uint8_t a_width) { + + if (a_width -= 2) { + write_register(SETUP_AW, a_width % 4); + addr_width = (a_width % 4) + 2; + } else { + write_register(SETUP_AW, 0); + addr_width = 2; + } + +} + + +void NRF24L01::openReadingPipe(uint8_t child, const uint8_t* address) { + // If this is pipe 0, cache the address. This is needed because + // openWritingPipe() will overwrite the pipe 0 address, so + // startListening() will have to restore it. + if (child == 0) { + memcpy(pipe0_reading_address, address, addr_width); + } + if (child <= 5) { + // For pipes 2-5, only write the LSB + if (child < 2) { + write_register(pgm_read_byte(&child_pipe[child]), address, addr_width); + } else { + write_register(pgm_read_byte(&child_pipe[child]), address, 1); + } + write_register(pgm_read_byte(&child_payload_size[child]), payload_size); + + // Note it would be more efficient to set all of the bits for all open + // pipes at once. However, I thought it would make the calling code + // more simple to do it this way. + write_register(EN_RXADDR, read_register(EN_RXADDR) | _BV(pgm_read_byte(&child_pipe_enable[child]))); + + } +} + +/****************************************************************************/ + +void NRF24L01::closeReadingPipe(uint8_t pipe) { + write_register(EN_RXADDR, read_register(EN_RXADDR) & ~_BV(pgm_read_byte(&child_pipe_enable[pipe]))); +} + + +void NRF24L01::toggle_features(void) { + beginTransaction(); + _SPI.transfer(ACTIVATE); + _SPI.transfer(0x73); + endTransaction(); +} + + +void NRF24L01::enableDynamicPayloads(void) { + // Enable dynamic payload throughout the system + + //toggle_features(); + write_register(FEATURE, read_register(FEATURE) | _BV(EN_DPL)); + + // IF_SERIAL_DEBUG(printf("FEATURE=%i\r\n", read_register(FEATURE))); + + // Enable dynamic payload on all pipes + // + // Not sure the use case of only having dynamic payload on certain + // pipes, so the library does not support it. + write_register(DYNPD, read_register(DYNPD) | _BV(DPL_P5) | _BV(DPL_P4) | _BV(DPL_P3) | _BV(DPL_P2) | _BV(DPL_P1) | _BV(DPL_P0)); + + dynamic_payloads_enabled = true; +} + +/****************************************************************************/ +void NRF24L01::disableDynamicPayloads(void) { + // Disables dynamic payload throughout the system. Also disables Ack Payloads + + //toggle_features(); + write_register(FEATURE, 0); + + // IF_SERIAL_DEBUG(printf("FEATURE=%i\r\n", read_register(FEATURE))); + + // Disable dynamic payload on all pipes + // + // Not sure the use case of only having dynamic payload on certain + // pipes, so the library does not support it. + write_register(DYNPD, 0); + + dynamic_payloads_enabled = false; + ack_payloads_enabled = false; +} + + +void NRF24L01::enableAckPayload(void) { + // + // enable ack payload and dynamic payload features + // + + //toggle_features(); + write_register(FEATURE, read_register(FEATURE) | _BV(EN_ACK_PAY) | _BV(EN_DPL)); + + // IF_SERIAL_DEBUG(printf("FEATURE=%i\r\n", read_register(FEATURE))); + + // + // Enable dynamic payload on pipes 0 & 1 + // + write_register(DYNPD, read_register(DYNPD) | _BV(DPL_P1) | _BV(DPL_P0)); + dynamic_payloads_enabled = true; + ack_payloads_enabled = true; +} + + +void NRF24L01::enableDynamicAck(void) { + // + // enable dynamic ack features + // + //toggle_features(); + write_register(FEATURE, read_register(FEATURE) | _BV(EN_DYN_ACK)); + // IF_SERIAL_DEBUG(printf("FEATURE=%i\r\n", read_register(FEATURE))); +} + + +void NRF24L01::writeAckPayload(uint8_t pipe, const void* buf, uint8_t len) { + const uint8_t* current = reinterpret_cast(buf); + + uint8_t data_len = rf24_min(len, 32); + + beginTransaction(); + _SPI.transfer(W_ACK_PAYLOAD | (pipe & 0x07)); + + while (data_len--) { + _SPI.transfer(*current++); + } + endTransaction(); +} + + +bool NRF24L01::isAckPayloadAvailable(void) { + return available(NULL); +} + + +bool NRF24L01::isPVariant(void) +{ + rf24_datarate_e dR = getDataRate(); + bool result = setDataRate(RF24_250KBPS); + setDataRate(dR); + return result; +} + + +void NRF24L01::setAutoAck(bool enable) { + if (enable) { + write_register(EN_AA, 0x3F); + } else { + write_register(EN_AA, 0); + } +} + + +void NRF24L01::setAutoAck(uint8_t pipe, bool enable) { + if (pipe <= 6) { + uint8_t en_aa = read_register(EN_AA); + if (enable) { + en_aa |= _BV(pipe); + } else { + en_aa &= ~_BV(pipe); + } + write_register(EN_AA, en_aa); + } +} + + +bool NRF24L01::testCarrier(void) { + return (read_register(CD) & 1); +} + + +bool NRF24L01::testRPD(void) { + return (read_register(RPD) & 1); +} + + +void NRF24L01::setPALevel(uint8_t level, bool lnaEnable) { + + uint8_t setup = read_register(RF_SETUP) & 0xF8; + + if(level > 3) { // If invalid level, go to max PA + level = (RF24_PA_MAX << 1) + lnaEnable; // +1 to support the SI24R1 chip extra bit + } else { + level = (level << 1) + lnaEnable; // Else set level as requested + } + + write_register(RF_SETUP, setup |= level); // Write it to the chip +} + + +uint8_t NRF24L01::getPALevel(void) { + return (read_register(RF_SETUP) & (_BV(RF_PWR_LOW) | _BV(RF_PWR_HIGH))) >> 1; +} + + +uint8_t NRF24L01::getARC(void) { + return read_register(OBSERVE_TX) & 0x0F; +} + + +bool NRF24L01::setDataRate(rf24_datarate_e speed) { + bool result = false; + uint8_t setup = read_register(RF_SETUP); + + // HIGH and LOW '00' is 1Mbs - our default + setup &= ~(_BV(RF_DR_LOW) | _BV(RF_DR_HIGH)); + + #if !defined(F_CPU) || F_CPU > 20000000 + txDelay = 280; + #else //16Mhz Arduino + txDelay=85; + #endif + if(speed == RF24_250KBPS) { + // Must set the RF_DR_LOW to 1; RF_DR_HIGH (used to be RF_DR) is already 0 + // Making it '10'. + setup |= _BV(RF_DR_LOW); + #if !defined(F_CPU) || F_CPU > 20000000 + txDelay = 505; + #else //16Mhz Arduino + txDelay = 155; + #endif + } else { + // Set 2Mbs, RF_DR (RF_DR_HIGH) is set 1 + // Making it '01' + if (speed == RF24_2MBPS) { + setup |= _BV(RF_DR_HIGH); + #if !defined(F_CPU) || F_CPU > 20000000 + txDelay = 240; + #else // 16Mhz Arduino + txDelay = 65; + #endif + } + } + write_register(RF_SETUP, setup); + + // Verify our result + if (read_register(RF_SETUP) == setup) { + result = true; + } + return result; +} + +/****************************************************************************/ + +rf24_datarate_e NRF24L01::getDataRate(void) { + rf24_datarate_e result; + uint8_t dr = read_register(RF_SETUP) & (_BV(RF_DR_LOW) | _BV(RF_DR_HIGH)); + + // switch uses RAM (evil!) + // Order matters in our case below + if(dr == _BV(RF_DR_LOW)) { + // '10' = 250KBPS + result = RF24_250KBPS; + } else if (dr == _BV(RF_DR_HIGH)) { + // '01' = 2MBPS + result = RF24_2MBPS; + } else { + // '00' = 1MBPS + result = RF24_1MBPS; + } + return result; +} + + +void NRF24L01::setCRCLength(rf24_crclength_e length) { + config_reg &= ~(_BV(CRCO) | _BV(EN_CRC)); + + // switch uses RAM (evil!) + if(length == RF24_CRC_DISABLED) { + // Do nothing, we turned it off above. + } else if(length == RF24_CRC_8) { + config_reg |= _BV(EN_CRC); + } else { + config_reg |= _BV(EN_CRC); + config_reg |= _BV(CRCO); + } + write_register(NRF_CONFIG, config_reg); +} + + +rf24_crclength_e NRF24L01::getCRCLength(void) { + rf24_crclength_e result = RF24_CRC_DISABLED; + uint8_t AA = read_register(EN_AA); + config_reg = read_register(NRF_CONFIG); + + if(config_reg & _BV(EN_CRC) || AA) { + if(config_reg & _BV(CRCO)) { + result = RF24_CRC_16; + } else { + result = RF24_CRC_8; + } + } + + return result; +} + + +void NRF24L01::disableCRC(void) { + config_reg &= ~_BV(EN_CRC); + write_register(NRF_CONFIG, config_reg); +} + + +void NRF24L01::setRetries(uint8_t delay, uint8_t count) { + write_register(SETUP_RETR, (delay & 0xf) << ARD | (count & 0xf) << ARC); +} + + +void NRF24L01::startConstCarrier(rf24_pa_dbm_e level, uint8_t channel) { + write_register(RF_SETUP, (read_register(RF_SETUP)) | _BV(CONT_WAVE)); + write_register(RF_SETUP, (read_register(RF_SETUP)) | _BV(PLL_LOCK)); + setPALevel(level); + setChannel(channel); + // IF_SERIAL_DEBUG( printf_P(PSTR("RF_SETUP=%02x\r\n"), read_register(RF_SETUP) ) ); + ce(HIGH); +} + + +void NRF24L01::stopConstCarrier() { + write_register(RF_SETUP, (read_register(RF_SETUP)) & ~_BV(CONT_WAVE)); + write_register(RF_SETUP, (read_register(RF_SETUP)) & ~_BV(PLL_LOCK)); + ce(LOW); +} + + +NRF24L01 rx(RX_CE_PIN, RX_CSN_PIN); // Setting up receiver module diff --git a/src/nrf24l01.h b/src/nrf24l01.h new file mode 100644 index 0000000..b12ce81 --- /dev/null +++ b/src/nrf24l01.h @@ -0,0 +1,1360 @@ +/* + * Filename: nrf24l01.h + * Date: Sat 13 Nov 19:33:42 +08 2021 + * Author: Englebert + * Description: + * This is a re-write nRF24L01 driver for ESP32. It will use the fastest way to + * communicate. It utilized the DMA way to maximized the data transfer rate. + * + * Copyright (C) + * 2011 J. Coliz + * 2015-2019 TMRh20 + * 2015 spaniakos + * 2015 nerdralph + * 2015 zador-blood-stained + * 2016 akatran + * 2017-2019 Avamander + * 2019 IkpeohaGodson + * 2021 Englebert + * + * 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 _NRF24L01_H +#define _NRF24L01_H + +#include +#include +#include +#include "main.h" + +/* 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 + +#define rf24_max(a,b) (a>b?a:b) +#define rf24_min(a,b) (a + * + * @note Users can specify default SPI speed by modifying `#define RF24_SPI_SPEED` in RF24_config.h
+ * For Arduino, SPI speed will only be properly configured this way on devices supporting SPI TRANSACTIONS
+ * Older/Unsupported Arduino devices will use a default clock divider & settings configuration
+ * Linux: The old way of setting SPI speeds using BCM2835 driver enums has been removed
+ * + * @param _cepin The pin attached to Chip Enable on the RF module + * @param _cspin The pin attached to Chip Select + * @param _spispeed The SPI speed in Hz ie: 1000000 == 1Mhz + */ + NRF24L01(uint16_t _cepin, uint16_t _cspin, uint32_t _spispeed = RF24_SPI_SPEED); + + /** + * Begin operation of the chip + * + * Call this in setup(), before calling any other methods. + * @code radio.begin() @endcode + */ + bool begin(void); + + /** + * Checks if the chip is connected to the SPI bus + */ + bool isChipConnected(); + + /** + * Start listening on the pipes opened for reading. + * + * 1. Be sure to call openReadingPipe() first. + * 2. Do not call write() while in this mode, without first calling stopListening(). + * 3. Call available() to check for incoming traffic, and read() to get it. + * + * @code + * Open reading pipe 1 using address CCCECCCECC + * + * byte address[] = { 0xCC,0xCE,0xCC,0xCE,0xCC }; + * radio.openReadingPipe(1,address); + * radio.startListening(); + * @endcode + */ + void startListening(void); + + /** + * Stop listening for incoming messages, and switch to transmit mode. + * + * Do this before calling write(). + * @code + * radio.stopListening(); + * radio.write(&data,sizeof(data)); + * @endcode + */ + void stopListening(void); + + /** + * Check whether there are bytes available to be read + * @code + * if(radio.available()){ + * radio.read(&data,sizeof(data)); + * } + * @endcode + * @return True if there is a payload available, false if none is + */ + bool available(void); + + /** + * Read from the available payload + * + * The length of data read should the next available payload's length + * @sa getPayloadSize(), getDynamicPayloadSize() + * + * @note I specifically chose 'void*' as a data type to make it easier + * for beginners to use. No casting needed. + * + * @note No longer boolean. Use available to determine if packets are + * available. Interrupt flags are now cleared during reads instead of + * when calling available(). + * + * @param buf Pointer to a buffer where the data should be written + * @param len Maximum number of bytes to read into the buffer. This + * value should match the length of the object referenced using the + * `buf` parameter. There is no bounds checking implemented here. + * + * @code + * if(radio.available()){ + * radio.read(&data,sizeof(data)); + * } + * @endcode + * @return No return value. Use available(). + * @remark Remember that each call to read() fetches data from the + * RX FIFO beginning with the first byte from the first available + * payload. A payload is not removed from the RX FIFO until it's + * entire length (or more) is fetched using read(). + * @remarks + * - If `len` parameter's value is less than the available payload's + * length, then the payload remains in the RX FIFO. + * - If `len` parameter's value is greater than the first of multiple + * available payloads, then the data returned to the `buf` + * parameter's object will be supplemented with data from the next + * available payload. + * - If `len` parameter's value is greater than the last available + * payload's length, then the last byte in the payload is used as + * padding for the data returned to the `buf` parameter's object. + * The nRF24L01 will continue returning the last byte from the last + * payload even when read() is called with an empty RX FIFO. + */ + void read(void* buf, uint8_t len); + + /** + * Be sure to call openWritingPipe() first to set the destination + * of where to write to. + * + * This blocks until the message is successfully acknowledged by + * the receiver or the timeout/retransmit maxima are reached. In + * the current configuration, the max delay here is 60-70ms. + * + * The maximum size of data written is the fixed payload size, see + * getPayloadSize(). However, you can write less, and the remainder + * will just be filled with zeroes. + * + * TX/RX/RT interrupt flags will be cleared every time write is called + * + * @param buf Pointer to the data to be sent + * @param len Number of bytes to be sent + * + * @code + * radio.stopListening(); + * radio.write(&data,sizeof(data)); + * @endcode + * @return True if the payload was delivered successfully and an ACK was received, or upon successfull transmission if auto-ack is disabled. + */ + bool write(const void* buf, uint8_t len); + + /** + * New: Open a pipe for writing via byte array. Old addressing format retained + * for compatibility. + * + * Only one writing pipe can be open at once, but you can change the address + * you'll write to. Call stopListening() first. + * + * Addresses are assigned via a byte array, default is 5 byte address length + s * + * @code + * uint8_t addresses[][6] = {"1Node","2Node"}; + * radio.openWritingPipe(addresses[0]); + * @endcode + * @code + * uint8_t address[] = { 0xCC,0xCE,0xCC,0xCE,0xCC }; + * radio.openWritingPipe(address); + * address[0] = 0x33; + * radio.openReadingPipe(1,address); + * @endcode + * @see setAddressWidth + * + * @param address The address of the pipe to open. Coordinate these pipe + * addresses amongst nodes on the network. + */ + + void openWritingPipe(const uint8_t* address); + + /** + * Open a pipe for reading + * + * Up to 6 pipes can be open for reading at once. Open all the required + * reading pipes, and then call startListening(). + * + * @see openWritingPipe + * @see setAddressWidth + * + * @note Pipes 0 and 1 will store a full 5-byte address. Pipes 2-5 will technically + * only store a single byte, borrowing up to 4 additional bytes from pipe #1 per the + * assigned address width. + * @warning Pipes 1-5 should share the same address, except the first byte. + * Only the first byte in the array should be unique, e.g. + * @code + * uint8_t addresses[][6] = {"1Node","2Node"}; + * openReadingPipe(1,addresses[0]); + * openReadingPipe(2,addresses[1]); + * @endcode + * + * @warning Pipe 0 is also used by the writing pipe so should typically be avoided as a reading pipe.
+ * If used, the reading pipe 0 address needs to be restored at avery call to startListening(), and the address
+ * is ONLY restored if the LSB is a non-zero value.
See http://maniacalbits.blogspot.com/2013/04/rf24-addressing-nrf24l01-radios-require.html + * + * @param number Which pipe# to open, 0-5. + * @param address The 24, 32 or 40 bit address of the pipe to open. + */ + + void openReadingPipe(uint8_t number, const uint8_t* address); + + /**@}*/ + /** + * @name Advanced Operation + * + * Methods you can use to drive the chip in more advanced ways + */ + /**@{*/ + + /** + * Print a giant block of debugging information to stdout + * + * @warning Does nothing if stdout is not defined. See fdevopen in stdio.h + * The printf.h file is included with the library for Arduino. + * @code + * #include + * setup(){ + * Serial.begin(115200); + * printf_begin(); + * ... + * } + * @endcode + */ + void printDetails(void); + + /** + * Test whether there are bytes available to be read in the + * FIFO buffers. + * + * @param[out] pipe_num Which pipe has the payload available + * + * @code + * uint8_t pipeNum; + * if(radio.available(&pipeNum)){ + * radio.read(&data,sizeof(data)); + * Serial.print("Got data on pipe"); + * Serial.println(pipeNum); + * } + * @endcode + * @return True if there is a payload available, false if none is + */ + bool available(uint8_t* pipe_num); + + /** + * Check if the radio needs to be read. Can be used to prevent data loss + * @return True if all three 32-byte radio buffers are full + */ + bool rxFifoFull(); + + /** + * Enter low-power mode + * + * To return to normal power mode, call powerUp(). + * + * @note After calling startListening(), a basic radio will consume about 13.5mA + * at max PA level. + * During active transmission, the radio will consume about 11.5mA, but this will + * be reduced to 26uA (.026mA) between sending. + * In full powerDown mode, the radio will consume approximately 900nA (.0009mA) + * + * @code + * radio.powerDown(); + * avr_enter_sleep_mode(); // Custom function to sleep the device + * radio.powerUp(); + * @endcode + */ + void powerDown(void); + + /** + * Leave low-power mode - required for normal radio operation after calling powerDown() + * + * To return to low power mode, call powerDown(). + * @note This will take up to 5ms for maximum compatibility + */ + void powerUp(void); + + /** + * Write for single NOACK writes. Optionally disables acknowledgements/autoretries for a single write. + * + * @note enableDynamicAck() must be called to enable this feature + * + * Can be used with enableAckPayload() to request a response + * @see enableDynamicAck() + * @see setAutoAck() + * @see write() + * + * @param buf Pointer to the data to be sent + * @param len Number of bytes to be sent + * @param multicast Request ACK (0), NOACK (1) + */ + bool write(const void* buf, uint8_t len, const bool multicast); + + /** + * This will not block until the 3 FIFO buffers are filled with data. + * Once the FIFOs are full, writeFast will simply wait for success or + * timeout, and return 1 or 0 respectively. From a user perspective, just + * keep trying to send the same data. The library will keep auto retrying + * the current payload using the built in functionality. + * @warning It is important to never keep the nRF24L01 in TX mode and FIFO full for more than 4ms at a time. If the auto + * retransmit is enabled, the nRF24L01 is never in TX mode long enough to disobey this rule. Allow the FIFO + * to clear by issuing txStandBy() or ensure appropriate time between transmissions. + * + * @code + * Example (Partial blocking): + * + * radio.writeFast(&buf,32); // Writes 1 payload to the buffers + * txStandBy(); // Returns 0 if failed. 1 if success. Blocks only until MAX_RT timeout or success. Data flushed on fail. + * + * radio.writeFast(&buf,32); // Writes 1 payload to the buffers + * txStandBy(1000); // Using extended timeouts, returns 1 if success. Retries failed payloads for 1 seconds before returning 0. + * @endcode + * + * @see txStandBy() + * @see write() + * @see writeBlocking() + * + * @param buf Pointer to the data to be sent + * @param len Number of bytes to be sent + * @return True if the payload was delivered successfully false if not + */ + bool writeFast(const void* buf, uint8_t len); + + /** + * WriteFast for single NOACK writes. Disables acknowledgements/autoretries for a single write. + * + * @note enableDynamicAck() must be called to enable this feature + * @see enableDynamicAck() + * @see setAutoAck() + * + * @param buf Pointer to the data to be sent + * @param len Number of bytes to be sent + * @param multicast Request ACK (0) or NOACK (1) + */ + bool writeFast(const void* buf, uint8_t len, const bool multicast); + + /** + * This function extends the auto-retry mechanism to any specified duration. + * It will not block until the 3 FIFO buffers are filled with data. + * If so the library will auto retry until a new payload is written + * or the user specified timeout period is reached. + * @warning It is important to never keep the nRF24L01 in TX mode and FIFO full for more than 4ms at a time. If the auto + * retransmit is enabled, the nRF24L01 is never in TX mode long enough to disobey this rule. Allow the FIFO + * to clear by issuing txStandBy() or ensure appropriate time between transmissions. + * + * @code + * Example (Full blocking): + * + * radio.writeBlocking(&buf,32,1000); //Wait up to 1 second to write 1 payload to the buffers + * txStandBy(1000); //Wait up to 1 second for the payload to send. Return 1 if ok, 0 if failed. + * //Blocks only until user timeout or success. Data flushed on fail. + * @endcode + * @note If used from within an interrupt, the interrupt should be disabled until completion, and sei(); called to enable millis(). + * @see txStandBy() + * @see write() + * @see writeFast() + * + * @param buf Pointer to the data to be sent + * @param len Number of bytes to be sent + * @param timeout User defined timeout in milliseconds. + * @return True if the payload was loaded into the buffer successfully false if not + */ + bool writeBlocking(const void* buf, uint8_t len, uint32_t timeout); + + /** + * This function should be called as soon as transmission is finished to + * drop the radio back to STANDBY-I mode. If not issued, the radio will + * remain in STANDBY-II mode which, per the data sheet, is not a recommended + * operating mode. + * + * @note When transmitting data in rapid succession, it is still recommended by + * the manufacturer to drop the radio out of TX or STANDBY-II mode if there is + * time enough between sends for the FIFOs to empty. This is not required if auto-ack + * is enabled. + * + * Relies on built-in auto retry functionality. + * + * @code + * Example (Partial blocking): + * + * radio.writeFast(&buf,32); + * radio.writeFast(&buf,32); + * radio.writeFast(&buf,32); //Fills the FIFO buffers up + * bool ok = txStandBy(); //Returns 0 if failed. 1 if success. + * //Blocks only until MAX_RT timeout or success. Data flushed on fail. + * @endcode + * @see txStandBy(unsigned long timeout) + * @return True if transmission is successful + * + */ + bool txStandBy(); + + /** + * This function allows extended blocking and auto-retries per a user defined timeout + * @code + * Fully Blocking Example: + * + * radio.writeFast(&buf,32); + * radio.writeFast(&buf,32); + * radio.writeFast(&buf,32); //Fills the FIFO buffers up + * bool ok = txStandBy(1000); //Returns 0 if failed after 1 second of retries. 1 if success. + * //Blocks only until user defined timeout or success. Data flushed on fail. + * @endcode + * @note If used from within an interrupt, the interrupt should be disabled until completion, and sei(); called to enable millis(). + * @param timeout Number of milliseconds to retry failed payloads + * @param startTx If this is set to `true`, then this function puts the nRF24L01 + * in TX Mode. `false` leaves the primary mode (TX or RX) as it is, which can + * prevent the mandatory wait time to change modes. + * @return True if transmission is successful + * + */ + bool txStandBy(uint32_t timeout, bool startTx = 0); + + /** + * Write an ack payload for the specified pipe + * + * The next time a message is received on @p pipe, the data in @p buf will + * be sent back in the acknowledgement. + * @see enableAckPayload() + * @see enableDynamicPayloads() + * @warning Only three of these can be pending at any time as there are only 3 FIFO buffers.
Dynamic payloads must be enabled. + * @note Ack payloads are handled automatically by the radio chip when a payload is received. Users should generally + * write an ack payload as soon as startListening() is called, so one is available when a regular payload is received. + * @note Ack payloads are dynamic payloads. This only works on pipes 0&1 by default. Call + * enableDynamicPayloads() to enable on all pipes. + * + * @param pipe Which pipe# (typically 1-5) will get this response. + * @param buf Pointer to data that is sent + * @param len Length of the data to send, up to 32 bytes max. Not affected + * by the static payload set by setPayloadSize(). + */ + void writeAckPayload(uint8_t pipe, const void* buf, uint8_t len); + + /** + * Determine if an ack payload was received in the most recent call to + * write(). The regular available() can also be used. + * + * Call read() to retrieve the ack payload. + * + * @return True if an ack payload is available. + */ + bool isAckPayloadAvailable(void); + + /** + * Call this when you get an interrupt to find out why + * + * Tells you what caused the interrupt, and clears the state of + * interrupts. + * + * @param[out] tx_ok The send was successful (TX_DS) + * @param[out] tx_fail The send failed, too many retries (MAX_RT) + * @param[out] rx_ready There is a message waiting to be read (RX_DS) + */ + void whatHappened(bool& tx_ok, bool& tx_fail, bool& rx_ready); + + /** + * Non-blocking write to the open writing pipe used for buffered writes + * + * @note Optimization: This function now leaves the CE pin high, so the radio + * will remain in TX or STANDBY-II Mode until a txStandBy() command is issued. Can be used as an alternative to startWrite() + * if writing multiple payloads at once. + * @warning It is important to never keep the nRF24L01 in TX mode with FIFO full for more than 4ms at a time. If the auto + * retransmit/autoAck is enabled, the nRF24L01 is never in TX mode long enough to disobey this rule. Allow the FIFO + * to clear by issuing txStandBy() or ensure appropriate time between transmissions. + * + * @see write() + * @see writeFast() + * @see startWrite() + * @see writeBlocking() + * + * For single noAck writes see: + * @see enableDynamicAck() + * @see setAutoAck() + * + * @param buf Pointer to the data to be sent + * @param len Number of bytes to be sent + * @param multicast Request ACK (0) or NOACK (1) + * @param startTx If this is set to `true`, then this function sets the + * nRF24L01's CE pin to active (enabling TX transmissions). `false` has no + * effect on the nRF24L01's CE pin. + * @return True if the payload was delivered successfully false if not + */ + void startFastWrite(const void* buf, uint8_t len, const bool multicast, bool startTx = 1); + + /** + * Non-blocking write to the open writing pipe + * + * Just like write(), but it returns immediately. To find out what happened + * to the send, catch the IRQ and then call whatHappened(). + * + * @see write() + * @see writeFast() + * @see startFastWrite() + * @see whatHappened() + * + * For single noAck writes see: + * @see enableDynamicAck() + * @see setAutoAck() + * + * @param buf Pointer to the data to be sent + * @param len Number of bytes to be sent + * @param multicast Request ACK (0) or NOACK (1) + * + */ + void startWrite(const void* buf, uint8_t len, const bool multicast); + + /** + * This function is mainly used internally to take advantage of the auto payload + * re-use functionality of the chip, but can be beneficial to users as well. + * + * The function will instruct the radio to re-use the data in the FIFO buffers, + * and instructs the radio to re-send once the timeout limit has been reached. + * Used by writeFast and writeBlocking to initiate retries when a TX failure + * occurs. Retries are automatically initiated except with the standard write(). + * This way, data is not flushed from the buffer until switching between modes. + * + * @note This is to be used AFTER auto-retry fails if wanting to resend + * using the built-in payload reuse features. + * After issuing reUseTX(), it will keep reending the same payload forever or until + * a payload is written to the FIFO, or a flush_tx command is given. + */ + void reUseTX(); + + /** + * Empty the transmit buffer. This is generally not required in standard operation. + * May be required in specific cases after stopListening() , if operating at 250KBPS data rate. + * + * @return Current value of status register + */ + uint8_t flush_tx(void); + + /** + * Test whether there was a carrier on the line for the + * previous listening period. + * + * Useful to check for interference on the current channel. + * + * @return true if was carrier, false if not + */ + bool testCarrier(void); + + /** + * Test whether a signal (carrier or otherwise) greater than + * or equal to -64dBm is present on the channel. Valid only + * on nRF24L01P (+) hardware. On nRF24L01, use testCarrier(). + * + * Useful to check for interference on the current channel and + * channel hopping strategies. + * + * @code + * bool goodSignal = radio.testRPD(); + * if(radio.available()){ + * Serial.println(goodSignal ? "Strong signal > 64dBm" : "Weak signal < 64dBm" ); + * radio.read(0,0); + * } + * @endcode + * @return true if signal => -64dBm, false if not + */ + bool testRPD(void); + + /** + * Test whether this is a real radio, or a mock shim for + * debugging. Setting either pin to 0xff is the way to + * indicate that this is not a real radio. + * + * @return true if this is a legitimate radio + */ + bool isValid() + { + return ce_pin != 0xff && csn_pin != 0xff; + } + + /** + * Close a pipe after it has been previously opened. + * Can be safely called without having previously opened a pipe. + * @param pipe Which pipe # to close, 0-5. + */ + void closeReadingPipe(uint8_t pipe); + + /** + * + * If a failure has been detected, it usually indicates a hardware issue. By default the library + * will cease operation when a failure is detected. + * This should allow advanced users to detect and resolve intermittent hardware issues. + * + * In most cases, the radio must be re-enabled via radio.begin(); and the appropriate settings + * applied after a failure occurs, if wanting to re-enable the device immediately. + * + * The three main failure modes of the radio include: + * + * Writing to radio: Radio unresponsive - Fixed internally by adding a timeout to the internal write functions in RF24 (failure handling) + * + * Reading from radio: Available returns true always - Fixed by adding a timeout to available functions by the user. This is implemented internally in RF24Network. + * + * Radio configuration settings are lost - Fixed by monitoring a value that is different from the default, and re-configuring the radio if this setting reverts to the default. + * + * See the included example, GettingStarted_HandlingFailures + * + * @code + * if(radio.failureDetected){ + * radio.begin(); // Attempt to re-configure the radio with defaults + * radio.failureDetected = 0; // Reset the detection value + * radio.openWritingPipe(addresses[1]); // Re-configure pipe addresses + * radio.openReadingPipe(1,addresses[0]); + * report_failure(); // Blink leds, send a message, etc. to indicate failure + * } + * @endcode + */ + //#if defined (FAILURE_HANDLING) + bool failureDetected; + //#endif + + /**@}*/ + /** + * @name Optional Configurators + * + * Methods you can use to get or set the configuration of the chip. + * None are required. Calling begin() sets up a reasonable set of + * defaults. + */ + /**@{*/ + + /** + * Set the address width from 3 to 5 bytes (24, 32 or 40 bit) + * + * @param a_width The address width to use: 3,4 or 5 + */ + + void setAddressWidth(uint8_t a_width); + + /** + * Set the number and delay of retries upon failed submit + * + * @param delay How long to wait between each retry, in multiples of 250us, + * max is 15. 0 means 250us, 15 means 4000us. + * @param count How many retries before giving up, max 15 + */ + void setRetries(uint8_t delay, uint8_t count); + + /** + * Set RF communication channel + * + * @param channel Which RF channel to communicate on, 0-125 + */ + void setChannel(uint8_t channel); + + /** + * Get RF communication channel + * + * @return The currently configured RF Channel + */ + uint8_t getChannel(void); + + /** + * Set Static Payload Size + * + * This implementation uses a pre-stablished fixed payload size for all + * transmissions. If this method is never called, the driver will always + * transmit the maximum payload size (32 bytes), no matter how much + * was sent to write(). + * + * @todo Implement variable-sized payloads feature + * + * @param size The number of bytes in the payload + */ + void setPayloadSize(uint8_t size); + + /** + * Get Static Payload Size + * + * @see setPayloadSize() + * + * @return The number of bytes in the payload + */ + uint8_t getPayloadSize(void); + + /** + * Get Dynamic Payload Size + * + * For dynamic payloads, this pulls the size of the payload off + * the chip + * + * @note Corrupt packets are now detected and flushed per the + * manufacturer. + * @code + * if(radio.available()){ + * if(radio.getDynamicPayloadSize() < 1){ + * // Corrupt payload has been flushed + * return; + * } + * radio.read(&data,sizeof(data)); + * } + * @endcode + * + * @return Payload length of last-received dynamic payload + */ + uint8_t getDynamicPayloadSize(void); + + /** + * Enable custom payloads on the acknowledge packets + * + * Ack payloads are a handy way to return data back to senders without + * manually changing the radio modes on both units. + * + * @note Ack payloads are dynamic payloads. This only works on pipes 0&1 by default. Call + * enableDynamicPayloads() to enable on all pipes. + */ + void enableAckPayload(void); + + /** + * Enable dynamically-sized payloads + * + * This way you don't always have to send large packets just to send them + * once in a while. This enables dynamic payloads on ALL pipes. + * + */ + void enableDynamicPayloads(void); + + /** + * Disable dynamically-sized payloads + * + * This disables dynamic payloads on ALL pipes. Since Ack Payloads + * requires Dynamic Payloads, Ack Payloads are also disabled. + * If dynamic payloads are later re-enabled and ack payloads are desired + * then enableAckPayload() must be called again as well. + * + */ + void disableDynamicPayloads(void); + + /** + * Enable dynamic ACKs (single write multicast or unicast) for chosen messages + * + * @note To enable full multicast or per-pipe multicast, use setAutoAck() + * + * @warning This MUST be called prior to attempting single write NOACK calls + * @code + * radio.enableDynamicAck(); + * radio.write(&data,32,1); // Sends a payload with no acknowledgement requested + * radio.write(&data,32,0); // Sends a payload using auto-retry/autoACK + * @endcode + */ + void enableDynamicAck(); + + /** + * Determine whether the hardware is an nRF24L01+ or not. + * + * @return true if the hardware is nRF24L01+ (or compatible) and false + * if its not. + */ + bool isPVariant(void); + + /** + * Enable or disable auto-acknowlede packets + * + * This is enabled by default, so it's only needed if you want to turn + * it off for some reason. + * + * @param enable Whether to enable (true) or disable (false) auto-acks + */ + void setAutoAck(bool enable); + + /** + * Enable or disable auto-acknowlede packets on a per pipeline basis. + * + * AA is enabled by default, so it's only needed if you want to turn + * it off/on for some reason on a per pipeline basis. + * + * @param pipe Which pipeline to modify + * @param enable Whether to enable (true) or disable (false) auto-acks + */ + void setAutoAck(uint8_t pipe, bool enable); + + /** + * Set Power Amplifier (PA) level to one of four levels: + * RF24_PA_MIN, RF24_PA_LOW, RF24_PA_HIGH and RF24_PA_MAX + * + * The power levels correspond to the following output levels respectively: + * NRF24L01: -18dBm, -12dBm,-6dBM, and 0dBm, lnaEnable affects modules with LNA + * + * SI24R1: -6dBm, 0dBm, 3dBm and 7dBm with lnaEnable = 1 + * -12dBm,-4dBm, 1dBm and 4dBm with lnaEnable = 0 + * + * @param level Desired PA level. + * @param lnaEnable En/Disable LNA Gain + */ + void setPALevel(uint8_t level, bool lnaEnable = 1); + + /** + * Fetches the current PA level. + * + * NRF24L01: -18dBm, -12dBm, -6dBm and 0dBm + * SI24R1: -6dBm, 0dBm, 3dBm, 7dBm + * + * @return Returns values 0 to 3 representing the PA Level. + */ + uint8_t getPALevel(void); + + /** + * Returns automatic retransmission count (ARC_CNT) + * + * Value resets with each new transmission. Allows roughly estimating signal strength. + * + * @return Returns values from 0 to 15. + */ + uint8_t getARC(void); + + /** + * Set the transmission data rate + * + * @warning setting RF24_250KBPS will fail for non-plus units + * + * @param speed RF24_250KBPS for 250kbs, RF24_1MBPS for 1Mbps, or RF24_2MBPS for 2Mbps + * @return true if the change was successful + */ + bool setDataRate(rf24_datarate_e speed); + + /** + * Fetches the transmission data rate + * + * @return Returns the hardware's currently configured datarate. The value + * is one of 250kbs, RF24_1MBPS for 1Mbps, or RF24_2MBPS, as defined in the + * rf24_datarate_e enum. + */ + rf24_datarate_e getDataRate(void); + + /** + * Set the CRC length + *
CRC checking cannot be disabled if auto-ack is enabled + * @param length RF24_CRC_8 for 8-bit or RF24_CRC_16 for 16-bit + */ + void setCRCLength(rf24_crclength_e length); + + /** + * Get the CRC length + *
CRC checking cannot be disabled if auto-ack is enabled + * @return RF24_CRC_DISABLED if disabled or RF24_CRC_8 for 8-bit or RF24_CRC_16 for 16-bit + */ + rf24_crclength_e getCRCLength(void); + + /** + * Disable CRC validation + * + * @warning CRC cannot be disabled if auto-ack/ESB is enabled. + */ + void disableCRC(void); + + /** + * The radio will generate interrupt signals when a transmission is complete, + * a transmission fails, or a payload is received. This allows users to mask + * those interrupts to prevent them from generating a signal on the interrupt + * pin. Interrupts are enabled on the radio chip by default. + * + * @code + * Mask all interrupts except the receive interrupt: + * + * radio.maskIRQ(1,1,0); + * @endcode + * + * @param tx_ok Mask transmission complete interrupts + * @param tx_fail Mask transmit failure interrupts + * @param rx_ready Mask payload received interrupts + */ + void maskIRQ(bool tx_ok, bool tx_fail, bool rx_ready); + + /** + * + * The driver will delay for this duration when stopListening() is called + * + * When responding to payloads, faster devices like ARM(RPi) are much faster than Arduino: + * 1. Arduino sends data to RPi, switches to RX mode + * 2. The RPi receives the data, switches to TX mode and sends before the Arduino radio is in RX mode + * 3. If AutoACK is disabled, this can be set as low as 0. If AA/ESB enabled, set to 100uS minimum on RPi + * + * @warning If set to 0, ensure 130uS delay after stopListening() and before any sends + */ + + uint32_t txDelay; + + /** + * + * On all devices but Linux and ATTiny, a small delay is added to the CSN toggling function + * + * This is intended to minimise the speed of SPI polling due to radio commands + * + * If using interrupts or timed requests, this can be set to 0 Default:5 + */ + + uint32_t csDelay; + + /** + * Transmission of constant carrier wave with defined frequency and output power + * + * @param level Output power to use + * @param channel The channel to use + */ + void startConstCarrier(rf24_pa_dbm_e level, uint8_t channel); + + /** + * Stop transmission of constant wave and reset PLL and CONT registers + */ + void stopConstCarrier(void); + + /**@}*/ + /** + * @name Deprecated + * + * Methods provided for backwards compabibility. + */ + /**@{*/ + + + /** + * Open a pipe for reading + * @note For compatibility with old code only, see new function + * + * @warning Pipes 1-5 should share the first 32 bits. + * Only the least significant byte should be unique, e.g. + * @code + * openReadingPipe(1,0xF0F0F0F0AA); + * openReadingPipe(2,0xF0F0F0F066); + * @endcode + * + * @warning Pipe 0 is also used by the writing pipe so should typically be avoided as a reading pipe.
+ * If used, the reading pipe 0 address needs to be restored at avery call to startListening(), and the address
+ * is ONLY restored if the LSB is a non-zero value.
See http://maniacalbits.blogspot.com/2013/04/rf24-addressing-nrf24l01-radios-require.html + * + * @param number Which pipe# to open, 0-5. + * @param address The 40-bit address of the pipe to open. + */ + void openReadingPipe(uint8_t number, uint64_t address); + + /** + * Open a pipe for writing + * @note For compatibility with old code only, see new function + * + * Addresses are 40-bit hex values, e.g.: + * + * @code + * openWritingPipe(0xF0F0F0F0F0); + * @endcode + * + * @param address The 40-bit address of the pipe to open. + */ + void openWritingPipe(uint64_t address); + + /** + * Empty the receive buffer + * + * @return Current value of status register + */ + uint8_t flush_rx(void); + + private: + + /** + * @name Low-level internal interface. + * + * Protected methods that address the chip directly. Regular users cannot + * ever call these. They are documented for completeness and for developers who + * may want to extend this class. + */ + /**@{*/ + + /** + * Set chip select pin + * + * Running SPI bus at PI_CLOCK_DIV2 so we don't waste time transferring data + * and best of all, we make use of the radio's FIFO buffers. A lower speed + * means we're less likely to effectively leverage our FIFOs and pay a higher + * AVR runtime cost as toll. + * + * @param mode HIGH to take this unit off the SPI bus, LOW to put it on + */ + void csn(bool mode); + + /** + * Set chip enable + * + * @param level HIGH to actively begin transmission or LOW to put in standby. Please see data sheet + * for a much more detailed description of this pin. + */ + void ce(bool level); + + /** + * Read a chunk of data in from a register + * + * @param reg Which register. Use constants from nRF24L01.h + * @param buf Where to put the data + * @param len How many bytes of data to transfer + * @return Current value of status register + */ + uint8_t read_register(uint8_t reg, uint8_t* buf, uint8_t len); + + /** + * Read single byte from a register + * + * @param reg Which register. Use constants from nRF24L01.h + * @return Current value of register @p reg + */ + uint8_t read_register(uint8_t reg); + + /** + * Write a chunk of data to a register + * + * @param reg Which register. Use constants from nRF24L01.h + * @param buf Where to get the data + * @param len How many bytes of data to transfer + * @return Current value of status register + */ + uint8_t write_register(uint8_t reg, const uint8_t* buf, uint8_t len); + + /** + * Write a single byte to a register + * + * @param reg Which register. Use constants from nRF24L01.h + * @param value The new value to write + * @return Current value of status register + */ + uint8_t write_register(uint8_t reg, uint8_t value); + + /** + * Write the transmit payload + * + * The size of data written is the fixed payload size, see getPayloadSize() + * + * @param buf Where to get the data + * @param len Number of bytes to be sent + * @return Current value of status register + */ + uint8_t write_payload(const void* buf, uint8_t len, const uint8_t writeType); + + /** + * Read the receive payload + * + * The size of data read is the fixed payload size, see getPayloadSize() + * + * @param buf Where to put the data + * @param len Maximum number of bytes to read + * @return Current value of status register + */ + uint8_t read_payload(void* buf, uint8_t len); + + /** + * Retrieve the current status of the chip + * + * @return Current value of status register + */ + uint8_t get_status(void); + + #if !defined (MINIMAL) + + /** + * Decode and print the given status to stdout + * + * @param status Status value to print + * + * @warning Does nothing if stdout is not defined. See fdevopen in stdio.h + */ + void print_status(uint8_t status); + + /** + * Decode and print the given 'observe_tx' value to stdout + * + * @param value The observe_tx value to print + * + * @warning Does nothing if stdout is not defined. See fdevopen in stdio.h + */ + void print_observe_tx(uint8_t value); + + /** + * Print the name and value of an 8-bit register to stdout + * + * Optionally it can print some quantity of successive + * registers on the same line. This is useful for printing a group + * of related registers on one line. + * + * @param name Name of the register + * @param reg Which register. Use constants from nRF24L01.h + * @param qty How many successive registers to print + */ + void print_byte_register(const char* name, uint8_t reg, uint8_t qty = 1); + + /** + * Print the name and value of a 40-bit address register to stdout + * + * Optionally it can print some quantity of successive + * registers on the same line. This is useful for printing a group + * of related registers on one line. + * + * @param name Name of the register + * @param reg Which register. Use constants from nRF24L01.h + * @param qty How many successive registers to print + */ + void print_address_register(const char* name, uint8_t reg, uint8_t qty = 1); + + #endif + + /** + * Turn on or off the special features of the chip + * + * The chip has certain 'features' which are only available when the 'features' + * are enabled. See the datasheet for details. + */ + void toggle_features(void); + + /** + * Built in spi transfer function to simplify repeating code repeating code + */ + + uint8_t spiTrans(uint8_t cmd); + + void errNotify(void); + + /**@}*/ + +}; // End of class RF24 + + +extern NRF24L01 rx; +#endif // _NRF24L01_H diff --git a/src/sbus.cpp b/src/sbus.cpp new file mode 100644 index 0000000..00eb609 --- /dev/null +++ b/src/sbus.cpp @@ -0,0 +1,197 @@ +// REFERENCES: +// https://www.circuitbasics.com/basics-uart-communication/ +// https://www.analog.com/en/analog-dialogue/articles/uart-a-hardware-communication-protocol.html +// https://github.com/uzh-rpg/rpg_quadrotor_control/wiki/SBUS-Protocol +// https://github.com/plerup/espsoftwareserial/blob/main/src/SoftwareSerial.cpp +// https://lucidar.me/en/serialib/most-used-baud-rates-table/ + +#include "sbus.h" + +// SBUS data structure +#define RC_CHANS 18 +#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 +#define SBUS_PORT 13 // Trigger pulse from the port + +uint8_t sbusPacket[SBUS_PACKET_LENGTH]; +int rcChannels[SBUS_CHANNEL_NUMBER]; +uint32_t sbusTime = 0; +bool signalNotOK = false; + +uint32_t counter = 900; +uint32_t last_count = 0; + + +SBUS::SBUS(void) { +} + +void SBUS::begin(void) { + pinMode(SBUS_PORT, OUTPUT); + + // ON it first as IDLE + GPOS = (1 << SBUS_PORT); + // swSer1.begin(220000, SWSERIAL_8E2, SBUS_PORT, SBUS_PORT, false, 256); + // swSer1.enableIntTx(false); + // swSer1.enableTx(true); +} + +void SBUS::run(void) { +} + +// Sending SBUS packets +void SBUS::writePackets(void) { + if((uint32_t)(millis() - sbusTime) > SBUS_UPDATE_RATE) { + if(signalNotOK) { + // DEBUG ONLY...later put back to 900 + rcChannels[2] = 1800; + rcChannels[3] = 900; + rcChannels[1] = 900; + rcChannels[0] = 900; + } + + sbusPreparePacket(sbusPacket, rcChannels, signalNotOK, false); + // Serial2.write(sbusPacket, SBUS_PACKET_LENGTH); + /// swSer1.write(sbusPacket, SBUS_PACKET_LENGTH); + + // Looping through the bytes - Generating Parity Bits + // Is using SBUS_FAST (200000 Baud), 8E2 (Even Parity and 2 bits stop + // For sending at 200000 baud, each bit used about 5uS + // Profiling each bits timing before sending + uint32_t clock_cycles_per_micro = 0; + uint32_t clock_cycles = 0; + uint32_t clock_cycles_total_start = millis(); + + while((uint32_t) millis() - clock_cycles_total_start < 1) { + clock_cycles_per_micro++; + } + + // bool tx_state = true; + uint8_t parity_count = 0; + uint8_t data_bits = 0; + bool current_bit = 0; + + + // Now we roughly know how much per clock cycles per microseconds + for(uint8_t pos = 0; pos < SBUS_PACKET_LENGTH; pos++) { + // Now we are going to send the data from LSB and with EVEN parity on each byte with 2 bits stop. + // Looping through each bytes with: + // START BIT | DATA FRAME | PARITY BITS | STOP BITS + + // START BIT - For 1 clock cycle = 5uS = clock_per_micro + // Set to LOW as start bit + GPOC = (1 << SBUS_PORT); + for(clock_cycles = 0; clock_cycles < clock_cycles_per_micro; clock_cycles++); + + // DATA FRAME + // Reading the data sending it byte by byte + for(data_bits = 0; data_bits < 8; data_bits++) { + current_bit = (sbusPacket[pos] >> data_bits) & 0x01; + // Sending it out... + if(current_bit) { + parity_count++; + + // HIGH + GPOS = (1 << SBUS_PORT); + } else { + // LOW + GPOC = (1 << SBUS_PORT); + } + for(clock_cycles = 0; clock_cycles < clock_cycles_per_micro; clock_cycles++); + } + + // PARITY BITS + // Parity Calculation + if(parity_count & 0x01) { + // ODD + // Need to make it EVEN.... + GPOS = (1 << SBUS_PORT); + } else { + // EVEN + // Nothing needs to be set + GPOC = (1 << SBUS_PORT); + } + for(clock_cycles = 0; clock_cycles < clock_cycles_per_micro; clock_cycles++); + + // STOP BITS + GPOS = (1 << SBUS_PORT); + for(clock_cycles = 0; clock_cycles < clock_cycles_per_micro; clock_cycles++); + for(clock_cycles = 0; clock_cycles < clock_cycles_per_micro; clock_cycles++); + } + + + // Wait for next round + sbusTime = millis(); + } +} + +// Preparing SBUS packets +void SBUS::sbusPreparePacket(uint8_t packet[], int channels[], bool isSignalLoss, bool isFailsafe){ + if(millis() - last_count > 2000) { + counter+= 100; + + if(counter > 2000) { + counter = 900; + } + + last_count = millis(); + } + static int output[SBUS_CHANNEL_NUMBER] = {0}; + + /* + * 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); + // DEBUG oNly + output[i] = counter; + } + + 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); + packet[23] = stateByte; //Flags byte + packet[24] = SBUS_FRAME_FOOTER; //Footer +} + +SBUS sbus; diff --git a/src/sbus.h b/src/sbus.h new file mode 100644 index 0000000..658f8c0 --- /dev/null +++ b/src/sbus.h @@ -0,0 +1,22 @@ +#ifndef SBUS_H_ +#define SBUS_H_ + +#include +// #include "SoftwareSerial.h" + +class SBUS { + public: + bool invert; + + SBUS(void); + void begin(void); + void run(void); + void sbusPreparePacket(uint8_t packet[], int channels[], bool isSignalLoss, bool isFailsafe); + void writePackets(void); + + private: + uint32_t last_wifi_check, wifi_check_duration; +}; + +extern SBUS sbus; +#endif diff --git a/test/README b/test/README new file mode 100644 index 0000000..b94d089 --- /dev/null +++ b/test/README @@ -0,0 +1,11 @@ + +This directory is intended for PlatformIO Unit Testing and project tests. + +Unit Testing is a software testing method by which individual units of +source code, sets of one or more MCU program modules together with associated +control data, usage procedures, and operating procedures, are tested to +determine whether they are fit for use. Unit testing finds problems early +in the development cycle. + +More information about PlatformIO Unit Testing: +- https://docs.platformio.org/page/plus/unit-testing.html