diff --git a/.github/ISSUE_TEMPLATE/bug-report.yml b/.github/ISSUE_TEMPLATE/bug-report.yml
index 14e02344..6ff26524 100644
--- a/.github/ISSUE_TEMPLATE/bug-report.yml
+++ b/.github/ISSUE_TEMPLATE/bug-report.yml
@@ -64,10 +64,12 @@ body:
- Arduino MKR WiFi 1010
- Arduino MKR ZERO
- Arduino Nano 33 IoT
+ - Arduino Nano RP2040 Connect
- Arduino Zero
- Espressif ESP32-C3 DevKitC-02
- Espressif ESP32-C3 DevKitM-1
- Espressif ESP32-S3 DevKitC-1-N8
+ - Raspberry Pi Pico RP2040
- Seeed Studio Xiao ESP32-C3
- Seeed Studio Xiao ESP32-S3
- Seeed Studio XIAO SAMD21
diff --git a/.gitignore b/.gitignore
index dde9c899..444fd770 100644
--- a/.gitignore
+++ b/.gitignore
@@ -4,9 +4,8 @@
# Artefacts for Visual Studio Code
.vscode/
-# PlatformIO specific README files
-src/platformio/include/README
-src/platformio/test/README
+# PlatformIO specific files
+test/README
# Template files for CRSF for Arduino
templates/
diff --git a/README.md b/README.md
index 8633548a..29f46e8d 100644
--- a/README.md
+++ b/README.md
@@ -66,6 +66,11 @@ Pro tips:
In PlatformIO, CRSF for Arduino's dependencies are automatically installed, when you build your project for the first time.
The `platformio.ini` file contains a list of development boards that is compatible with CRSF for Arduino.
+## Installation - Using as a dependency in your PlatformIO project
+
+Simply add `https://github.com/ZZ-Cat/CRSFforArduino.git @^ 1.0.0` to your `lib_deps` section in your `platformio.ini` file.
+PlatformIO will take care of the rest. This is fairly new, so any hiccups, don't hesitate to let me know via my Issues tab.
+
## Installation - Straight from the Main-Trunk
If you want bleeding edge features and want to help me out on developing CRSF for Arduino, this is how you go about it:
@@ -373,6 +378,9 @@ CRSF for Arduino is compatible with these development boards:
- SparkFun ESP32 Thing
- SparkFun ESP32 Thing Plus
- SparkFun ESP32-S2 Thing Plus
+- RP2040 based boards:
+ - Arduino Nano RP2040 Connect
+ - Raspberry Pi Pico RP2040
- SAMD21 based boards:
- Adafruit Feather M0 and all of its variants, including the Adafruit Feather M0 Express
- Adafruit ItsyBitsy M0 Express
diff --git a/examples/channels/channels.ino b/examples/channels/channels.ino
deleted file mode 100644
index 3aa6a189..00000000
--- a/examples/channels/channels.ino
+++ /dev/null
@@ -1,160 +0,0 @@
-/**
- * @file channels.ino
- * @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief This example sketch shows how to receive RC channels from a CRSF receiver using the CRSF for Arduino library.
- * @version 1.0.0
- * @date 2024-1-20
- *
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
- *
- * @section License GNU General Public License v3.0
- * This example sketch is a part of the CRSF for Arduino library.
- * CRSF for Arduino is free software: you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * CRSF for Arduino is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with CRSF for Arduino. If not, see .
- *
- * @section Introduction
- *
- * This example sketch shows how to receive RC channels from a CRSF receiver using the CRSFforArduino library.
- *
- * @section Hardware
- *
- * This example sketch was tested with the following hardware:
- * - Adafruit Metro M4 Express
- * - RadioMaster TX16S Max Edition (EdgeTX 2.8.0 or later)
- * - RadioMaster RP3 ExpressLRS 2.4GHz Nano Receiver (ExpressLRS 3.2.0 or later)
- * - RadioMaster Ranger ExpressLRS 2.4GHz Transmitter Module (ExpressLRS 3.2.0 or later)
- * - TBS Crossfire Micro TX Module
- * - TBS Crossfire Nano Diversity Receiver
- *
- * @section Dependencies
- *
- * PlatformIO will automatically install the following dependencies:
- * - Adafruit ZeroDMA Library
- *
- * @section Quick Start
- *
- * 1. Connect the receiver to the Metro M4 Express using the following pinout:
- * - TX pin to Metro M4 Express RX (Pin 0).
- * - RX pin to Metro M4 Express TX (Pin 1).
- * - GND pin to Metro M4 Express GND.
- * - 5V pin to Metro M4 Express 5V.
- * 2. Connect the Metro M4 Express to your computer using a USB cable.
- * 3. Build the firmware:
- * - Method 1: pio run
- * - Method 2: ctlr+alt+B
- * 4. Flash your Metro M4 Express.
- * - Method 1: pio run -t upload
- * - Method 2: ctlr+alt+U
- * 5. Configure the Serial Monitor:
- * - Port: Select the port that your Metro M4 Express is connected to.
- * - Baud Rate: 115200
- * - Line Ending: Both NL & CR
- * 6. Turn on your transmitter.
- * 7. Click "Start Monitoring" on the Serial Monitor.
- *
- * @section Binding (Optional & only needed for the first time)
- *
- * @par ExpressLRS:
- * Before you begin binding, make sure that you have the latest version of ExpressLRS flashed on your transmitter and receiver.
- * When you flash ExpressLRS, make sure that your transmitter and receiver have the same binding phrase.
- * 1. Turn on your transmitter.
- * 2. Power on your ELRS receiver - EG RadioMaster RP3.
- * 3. Binding will begin automatically, and the Status LED will turn solid when the receiver is bound.
- *
- * @par TBS Crossfire:
- * 1. Turn on your transmitter.
- * 2. On your transmitter, open up the TBS Agent Lite app.
- * - Radio Settings > Tools > TBS Agent Lite
- * 3. In TBS Agent Lite, select the Micro TX & enable Binding Mode.
- * - XF Micro TX > Bind > Execute
- * 4. Power on the Nano Diversity Receiver.
- * - If you have already powered on the receiver, power it off and then back on again.
- * - You do not need to hold the bind button on the receiver.
- * - Binding will begin automatically.
- * - The Status LED will turn solid green when the receiver is bound.
- * - The Status LED on the Micro TX will turn solid green when the receiver is bound.
- * 5. Close TBS Agent Lite.
- *
- * @section Output
- *
- * The Serial Monitor will display the following output:
- * @code
- * Channels Example
- * Ready
- * RC Channels
- * @endcode
- * The values for each channel will change as you move the sticks on your transmitter.
- * The values will be in microseconds (us).
- * Standard range is 988us to 2012us, with 1500us being the center position.
- * Extended range is 885us to 2115us, with 1500us being the center position.
- *
- */
-
-#if defined(ARDUINO) && defined(PLATFORMIO)
-#error "This example sketch is not compatible with PlatformIO. Please use the main_rc.cpp example instead."
-#elif defined(ARDUINO) && !defined(PLATFORMIO)
-
-#include "CRSFforArduino.hpp"
-
-const int channelCount = crsfProtocol::RC_CHANNEL_COUNT; // I'm not sure if this is right, but we can always manually put in the number of channels desired
-
-CRSFforArduino crsf = CRSFforArduino(&Serial1);
-
-void setup()
-{
- // Initialize the serial port & wait for the port to open.
- Serial.begin(115200);
- while (!Serial)
- {
- ;
- }
-
- // Initialize the CRSFforArduino library.
- if (!crsf.begin())
- {
- Serial.println("CRSF for Arduino initialization failed!");
- while (1)
- {
- ;
- }
- }
-
- // Show the user that the sketch is ready.
- Serial.println("RC Channels Example");
- delay(1000);
- Serial.println("Ready");
- delay(1000);
-}
-
-void loop()
-{
- crsf.update();
-
- /* Print RC channels every 100 ms. */
- static unsigned long lastPrint = 0;
- if (millis() - lastPrint >= 100)
- {
- lastPrint = millis();
- for (int i = 1; i <= channelCount; i++)
- {
- //Serial.print("Channel");
- Serial.print(i);
- Serial.print(":");
- Serial.print(crsf.rcToUs(crsf.getChannel(i)));
- Serial.print("\t");
- }
- Serial.println();
- }
-}
-
-#endif // defined(ARDUINO) && !defined(PLATFORMIO)
diff --git a/examples/flight_modes/flight_modes.ino b/examples/flight_modes/flight_modes.ino
index 0fdc49e0..d1c32ee9 100644
--- a/examples/flight_modes/flight_modes.ino
+++ b/examples/flight_modes/flight_modes.ino
@@ -1,14 +1,14 @@
/**
- * @file main_flight_modes.ino
+ * @file flight_modes.ino
* @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief Demonstrates the use of CRSF for Arduino's flight mode functionality.
+ * @brief Example of how to read flight modes from a receiver.
* @version 1.0.0
- * @date 2024-1-20
+ * @date 2024-2-9
*
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
+ * @copyright Copyright (c) 2024, Cassandra "ZZ Cat" Robinson. All rights reserved.
*
* @section License GNU General Public License v3.0
- * This [file type] is a part of the CRSF for Arduino library.
+ * This example is a part of the CRSF for Arduino library.
* CRSF for Arduino is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
@@ -23,9 +23,6 @@
* along with CRSF for Arduino. If not, see .
*
*/
-#if defined(ARDUINO) && defined(PLATFORMIO)
-#error "This example sketch is not compatible with PlatformIO. Please use the main_rc.cpp example instead."
-#elif defined(ARDUINO) && !defined(PLATFORMIO)
#include "CRSFforArduino.hpp"
@@ -61,7 +58,7 @@
CRSFforArduino crsf = CRSFforArduino(&Serial1);
-void onFlightModeUpdate(serialReceiver::flightModeId_t);
+void onFlightModeUpdate(serialReceiverLayer::flightModeId_t);
void setup()
{
@@ -85,7 +82,7 @@ void setup()
}
// Set flight modes.
- if (!crsf.setFlightMode(serialReceiver::FLIGHT_MODE_DISARMED, FLIGHT_MODE_ARM_CHANNEL, FLIGHT_MODE_ARM_MIN, FLIGHT_MODE_ARM_MAX))
+ if (!crsf.setFlightMode(serialReceiverLayer::FLIGHT_MODE_DISARMED, FLIGHT_MODE_ARM_CHANNEL, FLIGHT_MODE_ARM_MIN, FLIGHT_MODE_ARM_MAX))
{
Serial.println("Failed to set \"DISARMED\" flight mode!");
while (1)
@@ -94,7 +91,7 @@ void setup()
}
}
- if (!crsf.setFlightMode(serialReceiver::FLIGHT_MODE_ACRO, FLIGHT_MODE_ACRO_CHANNEL, FLIGHT_MODE_ACRO_MIN, FLIGHT_MODE_ACRO_MAX))
+ if (!crsf.setFlightMode(serialReceiverLayer::FLIGHT_MODE_ACRO, FLIGHT_MODE_ACRO_CHANNEL, FLIGHT_MODE_ACRO_MIN, FLIGHT_MODE_ACRO_MAX))
{
Serial.println("Failed to set \"ACRO\" flight mode!");
while (1)
@@ -103,7 +100,7 @@ void setup()
}
}
- if (!crsf.setFlightMode(serialReceiver::FLIGHT_MODE_ANGLE, FLIGHT_MODE_ANGLE_CHANNEL, FLIGHT_MODE_ANGLE_MIN, FLIGHT_MODE_ANGLE_MAX))
+ if (!crsf.setFlightMode(serialReceiverLayer::FLIGHT_MODE_ANGLE, FLIGHT_MODE_ANGLE_CHANNEL, FLIGHT_MODE_ANGLE_MIN, FLIGHT_MODE_ANGLE_MAX))
{
Serial.println("Failed to set \"ANGLE\" flight mode!");
while (1)
@@ -112,7 +109,7 @@ void setup()
}
}
- if (!crsf.setFlightMode(serialReceiver::FLIGHT_MODE_HORIZON, FLIGHT_MODE_HORIZON_CHANNEL, FLIGHT_MODE_HORIZON_MIN, FLIGHT_MODE_HORIZON_MAX))
+ if (!crsf.setFlightMode(serialReceiverLayer::FLIGHT_MODE_HORIZON, FLIGHT_MODE_HORIZON_CHANNEL, FLIGHT_MODE_HORIZON_MIN, FLIGHT_MODE_HORIZON_MAX))
{
Serial.println("Failed to set \"HORIZON\" flight mode!");
while (1)
@@ -136,43 +133,43 @@ void loop()
crsf.update();
}
-void onFlightModeUpdate(serialReceiver::flightModeId_t flightMode)
+void onFlightModeUpdate(serialReceiverLayer::flightModeId_t flightMode)
{
/* Here is where you would put your flight mode implementation.
For this example, we will just print the flight mode to the serial port,
and send it to the controller as telemetry. */
- static serialReceiver::flightModeId_t lastFlightMode = serialReceiver::FLIGHT_MODE_DISARMED;
+ static serialReceiverLayer::flightModeId_t lastFlightMode = serialReceiverLayer::FLIGHT_MODE_DISARMED;
if (flightMode != lastFlightMode)
{
Serial.print("Flight Mode: ");
switch (flightMode)
{
- case serialReceiver::FLIGHT_MODE_DISARMED:
+ case serialReceiverLayer::FLIGHT_MODE_DISARMED:
Serial.println("Disarmed");
break;
- case serialReceiver::FLIGHT_MODE_ACRO:
+ case serialReceiverLayer::FLIGHT_MODE_ACRO:
Serial.println("Acro");
break;
- case serialReceiver::FLIGHT_MODE_WAIT:
+ case serialReceiverLayer::FLIGHT_MODE_WAIT:
Serial.println("Wait for GPS Lock");
break;
- case serialReceiver::FLIGHT_MODE_FAILSAFE:
+ case serialReceiverLayer::FLIGHT_MODE_FAILSAFE:
Serial.println("Failsafe");
break;
- case serialReceiver::FLIGHT_MODE_GPS_RESCUE:
+ case serialReceiverLayer::FLIGHT_MODE_GPS_RESCUE:
Serial.println("GPS Rescue");
break;
- case serialReceiver::FLIGHT_MODE_PASSTHROUGH:
+ case serialReceiverLayer::FLIGHT_MODE_PASSTHROUGH:
Serial.println("Passthrough");
break;
- case serialReceiver::FLIGHT_MODE_ANGLE:
+ case serialReceiverLayer::FLIGHT_MODE_ANGLE:
Serial.println("Angle");
break;
- case serialReceiver::FLIGHT_MODE_HORIZON:
+ case serialReceiverLayer::FLIGHT_MODE_HORIZON:
Serial.println("Horizon");
break;
- case serialReceiver::FLIGHT_MODE_AIRMODE:
+ case serialReceiverLayer::FLIGHT_MODE_AIRMODE:
Serial.println("Airmode");
break;
default:
@@ -184,5 +181,3 @@ void onFlightModeUpdate(serialReceiver::flightModeId_t flightMode)
crsf.telemetryWriteFlightMode(flightMode);
}
}
-
-#endif
diff --git a/examples/link_stats/link_stats.ino b/examples/link_stats/link_stats.ino
new file mode 100644
index 00000000..14464200
--- /dev/null
+++ b/examples/link_stats/link_stats.ino
@@ -0,0 +1,100 @@
+/**
+ * @file link_stats.ino
+ * @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
+ * @brief Example of how to read link statistics from a receiver.
+ * @version 1.0.0
+ * @date 2024-2-9
+ *
+ * @copyright Copyright (c) 2024, Cassandra "ZZ Cat" Robinson. All rights reserved.
+ *
+ * @section License GNU General Public License v3.0
+ * This example is a part of the CRSF for Arduino library.
+ * CRSF for Arduino is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * CRSF for Arduino is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with CRSF for Arduino. If not, see .
+ *
+ */
+
+#include "CRSFforArduino.hpp"
+
+/* Tested with the following equipment:
+- Controller: RadioMaster TX16S Max Edition Mk1
+ - Firmware: EdgeTX 2.10.0 Nightly
+ - Lua Script: iNav OpenTX Telemetry Widget 2.2.3
+ - Transmitter Module: RadioMaster Ranger
+ - Firmware: ExpressLRS 3.3.1
+- Receiver: RadioMaster RP3 Diversity
+ - Firmware: ExpressLRS 3.3.1
+- Development Board: Adafruit Metro M4 Express
+ - Board Package: Adafruit SAMD Boards 1.7.5
+ - Framework: Arduino 1.8.13
+ - Library: CRSF for Arduino 1.0.0
+ */
+
+CRSFforArduino *crsf = nullptr;
+
+void onLinkStatisticsUpdate(serialReceiverLayer::link_statistics_t);
+
+void setup()
+{
+ Serial.begin(115200);
+ while (!Serial)
+ {
+ delay(10);
+ }
+
+ Serial.println("Link Statistics Example.");
+
+ crsf = new CRSFforArduino();
+
+ if (!crsf->begin())
+ {
+ Serial.println("CRSF for Arduino failed to initialise.");
+
+ delete crsf;
+ crsf = nullptr;
+
+ while (1)
+ {
+ delay(10);
+ }
+ }
+
+ // Set link statistics callback.
+ crsf->setLinkStatisticsCallback(onLinkStatisticsUpdate);
+
+ Serial.println("Ready.");
+ delay(1000);
+}
+
+void loop()
+{
+ crsf->update();
+}
+
+void onLinkStatisticsUpdate(serialReceiverLayer::link_statistics_t linkStatistics)
+{
+ static unsigned long lastPrint = 0;
+ if (millis() - lastPrint >= 200)
+ {
+ lastPrint = millis();
+ Serial.print("Link Statistics: ");
+ Serial.print("RSSI: ");
+ Serial.print(linkStatistics.rssi);
+ Serial.print(", Link Quality: ");
+ Serial.print(linkStatistics.lqi);
+ Serial.print(", Signal-to-Noise Ratio: ");
+ Serial.print(linkStatistics.snr);
+ Serial.print(", Transmitter Power: ");
+ Serial.println(linkStatistics.tx_power);
+ }
+}
diff --git a/examples/platformio/main.cpp b/examples/platformio/main.cpp
new file mode 100644
index 00000000..342a54d6
--- /dev/null
+++ b/examples/platformio/main.cpp
@@ -0,0 +1,103 @@
+/**
+ * @file main.cpp
+ * @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
+ * @brief This is the main development file for CRSF for Arduino.
+ * @version 1.0.0
+ * @date 2024-2-9
+ *
+ * @copyright Copyright (c) 2024, Cassandra "ZZ Cat" Robinson. All rights reserved.
+ *
+ * @section License GNU General Public License v3.0
+ * This source file is a part of the CRSF for Arduino library.
+ * CRSF for Arduino is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * CRSF for Arduino is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with CRSF for Arduino. If not, see .
+ *
+ */
+
+#include "Arduino.h"
+#include "CRSFforArduino.hpp"
+
+CRSFforArduino *crsf = nullptr;
+
+void onReceiveRcChannels(serialReceiverLayer::rcChannels_t *rcChannels);
+
+void setup()
+{
+ Serial.begin(115200);
+ while (!Serial)
+ {
+ delay(10);
+ }
+
+ crsf = new CRSFforArduino();
+
+ if (!crsf->begin())
+ {
+ Serial.println("CRSF for Arduino failed to initialise.");
+
+ delete crsf;
+ crsf = nullptr;
+
+ while (1)
+ {
+ delay(10);
+ }
+ }
+
+ crsf->setRcChannelsCallback(onReceiveRcChannels);
+}
+
+void loop()
+{
+ crsf->update();
+}
+
+void onReceiveRcChannels(serialReceiverLayer::rcChannels_t *rcChannels)
+{
+ static unsigned long lastPrint = millis();
+ if (millis() - lastPrint >= 100)
+ {
+ lastPrint = millis();
+
+ static bool initialised = false;
+ static bool lastFailSafe = false;
+ if (rcChannels->failsafe != lastFailSafe || !initialised)
+ {
+ initialised = true;
+ lastFailSafe = rcChannels->failsafe;
+ Serial.print("FailSafe: ");
+ Serial.println(lastFailSafe ? "Active" : "Inactive");
+ }
+
+ if (rcChannels->failsafe == false)
+ {
+ Serial.print("RC Channels rcToUs(rcChannels->value[0]));
+ Serial.print(", E: ");
+ Serial.print(crsf->rcToUs(rcChannels->value[1]));
+ Serial.print(", T: ");
+ Serial.print(crsf->rcToUs(rcChannels->value[2]));
+ Serial.print(", R: ");
+ Serial.print(crsf->rcToUs(rcChannels->value[3]));
+ Serial.print(", Aux1: ");
+ Serial.print(crsf->rcToUs(rcChannels->value[4]));
+ Serial.print(", Aux2: ");
+ Serial.print(crsf->rcToUs(rcChannels->value[5]));
+ Serial.print(", Aux3: ");
+ Serial.print(crsf->rcToUs(rcChannels->value[6]));
+ Serial.print(", Aux4: ");
+ Serial.print(crsf->rcToUs(rcChannels->value[7]));
+ Serial.println(">");
+ }
+ }
+}
diff --git a/examples/platformio/main_flight_modes.cpp b/examples/platformio/main_flight_modes.cpp
deleted file mode 100644
index 29a45b9f..00000000
--- a/examples/platformio/main_flight_modes.cpp
+++ /dev/null
@@ -1,187 +0,0 @@
-/**
- * @file main_flight_modes.cpp
- * @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief Demonstrates the use of CRSF for Arduino's flight mode functionality.
- * @version 1.0.0
- * @date 2024-1-20
- *
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
- *
- * @section License GNU General Public License v3.0
- * This [file type] is a part of the CRSF for Arduino library.
- * CRSF for Arduino is free software: you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * CRSF for Arduino is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with CRSF for Arduino. If not, see .
- *
- */
-#if defined(ARDUINO) && defined(PLATFORMIO)
-#include "Arduino.h"
-
-#include "CRSFforArduino.hpp"
-
-/* Tested with the following equipment:
-- Controller: RadioMaster TX16S Max Edition Mk1
- - Firmware: EdgeTX 2.10.0 Nightly
- - Lua Script: iNav OpenTX Telemetry Widget 2.2.3
- - Transmitter Module: RadioMaster Ranger
- - Firmware: ExpressLRS 3.3.1
-- Receiver: RadioMaster RP3 Diversity
- - Firmware: ExpressLRS 3.3.1
-- Development Board: Adafruit Metro M4 Express
- - Board Package: Adafruit SAMD Boards 1.7.5
- - Framework: Arduino 1.8.13
- - Library: CRSF for Arduino 0.5.0
- */
-
-#define FLIGHT_MODE_ARM_CHANNEL 5 // Set FLIGHT_MODE_ARM_CHANNEL to the channel that you want to use to simulate arming your drone.
-#define FLIGHT_MODE_ARM_MIN 1000
-#define FLIGHT_MODE_ARM_MAX 1800
-
-#define FLIGHT_MODE_ACRO_CHANNEL 8 // Set FLIGHT_MODE_ACRO_CHANNEL to the channel that you want to use to simulate acro mode.
-#define FLIGHT_MODE_ACRO_MIN 900
-#define FLIGHT_MODE_ACRO_MAX 1300
-
-#define FLIGHT_MODE_ANGLE_CHANNEL 8 // Set FLIGHT_MODE_ANGLE_CHANNEL to the channel that you want to use to simulate angle mode.
-#define FLIGHT_MODE_ANGLE_MIN 1300
-#define FLIGHT_MODE_ANGLE_MAX 1700
-
-#define FLIGHT_MODE_HORIZON_CHANNEL 8 // Set FLIGHT_MODE_HORIZON_CHANNEL to the channel that you want to use to simulate horizon mode.
-#define FLIGHT_MODE_HORIZON_MIN 1700
-#define FLIGHT_MODE_HORIZON_MAX 2100
-
-CRSFforArduino crsf = CRSFforArduino(&Serial1);
-
-void onFlightModeUpdate(serialReceiver::flightModeId_t);
-
-void setup()
-{
- // Initialise the Serial Port and wait for it to open.
- Serial.begin(115200);
- // while (!Serial)
- // {
- // ;
- // }
-
- Serial.println("Flight Modes Example");
-
- // Initialise CRSF for Arduino.
- if (!crsf.begin())
- {
- Serial.println("CRSF initialisation failed!");
- while (1)
- {
- ;
- }
- }
-
- // Set flight modes.
- if (!crsf.setFlightMode(serialReceiver::FLIGHT_MODE_DISARMED, FLIGHT_MODE_ARM_CHANNEL, FLIGHT_MODE_ARM_MIN, FLIGHT_MODE_ARM_MAX))
- {
- Serial.println("Failed to set \"DISARMED\" flight mode!");
- while (1)
- {
- ;
- }
- }
-
- if (!crsf.setFlightMode(serialReceiver::FLIGHT_MODE_ACRO, FLIGHT_MODE_ACRO_CHANNEL, FLIGHT_MODE_ACRO_MIN, FLIGHT_MODE_ACRO_MAX))
- {
- Serial.println("Failed to set \"ACRO\" flight mode!");
- while (1)
- {
- ;
- }
- }
-
- if (!crsf.setFlightMode(serialReceiver::FLIGHT_MODE_ANGLE, FLIGHT_MODE_ANGLE_CHANNEL, FLIGHT_MODE_ANGLE_MIN, FLIGHT_MODE_ANGLE_MAX))
- {
- Serial.println("Failed to set \"ANGLE\" flight mode!");
- while (1)
- {
- ;
- }
- }
-
- if (!crsf.setFlightMode(serialReceiver::FLIGHT_MODE_HORIZON, FLIGHT_MODE_HORIZON_CHANNEL, FLIGHT_MODE_HORIZON_MIN, FLIGHT_MODE_HORIZON_MAX))
- {
- Serial.println("Failed to set \"HORIZON\" flight mode!");
- while (1)
- {
- ;
- }
- }
-
- // Set flight mode callback.
- crsf.setFlightModeCallback(onFlightModeUpdate);
-
- Serial.print("\tArm channel: ");
- Serial.println(FLIGHT_MODE_ARM_CHANNEL);
- Serial.print("\tFlight Modes Channel: ");
- Serial.println(FLIGHT_MODE_ACRO_CHANNEL);
-}
-
-void loop()
-{
- // Update CRSF for Arduino.
- crsf.update();
-}
-
-void onFlightModeUpdate(serialReceiver::flightModeId_t flightMode)
-{
- /* Here is where you would put your flight mode implementation.
- For this example, we will just print the flight mode to the serial port,
- and send it to the controller as telemetry. */
- static serialReceiver::flightModeId_t lastFlightMode = serialReceiver::FLIGHT_MODE_DISARMED;
-
- if (flightMode != lastFlightMode)
- {
- Serial.print("Flight Mode: ");
- switch (flightMode)
- {
- case serialReceiver::FLIGHT_MODE_DISARMED:
- Serial.println("Disarmed");
- break;
- case serialReceiver::FLIGHT_MODE_ACRO:
- Serial.println("Acro");
- break;
- case serialReceiver::FLIGHT_MODE_WAIT:
- Serial.println("Wait for GPS Lock");
- break;
- case serialReceiver::FLIGHT_MODE_FAILSAFE:
- Serial.println("Failsafe");
- break;
- case serialReceiver::FLIGHT_MODE_GPS_RESCUE:
- Serial.println("GPS Rescue");
- break;
- case serialReceiver::FLIGHT_MODE_PASSTHROUGH:
- Serial.println("Passthrough");
- break;
- case serialReceiver::FLIGHT_MODE_ANGLE:
- Serial.println("Angle");
- break;
- case serialReceiver::FLIGHT_MODE_HORIZON:
- Serial.println("Horizon");
- break;
- case serialReceiver::FLIGHT_MODE_AIRMODE:
- Serial.println("Airmode");
- break;
- default:
- Serial.println("Unknown");
- break;
- }
- lastFlightMode = flightMode;
-
- crsf.telemetryWriteFlightMode(flightMode);
- }
-}
-
-#endif
diff --git a/examples/platformio/main_rc.cpp b/examples/platformio/main_rc.cpp
deleted file mode 100644
index 8848934b..00000000
--- a/examples/platformio/main_rc.cpp
+++ /dev/null
@@ -1,92 +0,0 @@
-/**
- * @file main_rc.cpp
- * @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief This file demonstrates the full capabilities of CRSF for Arduino.
- * @version 1.0.0
- * @date 2024-1-20
- *
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
- *
- * @section License GNU General Public License v3.0
- * This main file is a part of the CRSF for Arduino library.
- * CRSF for Arduino is free software: you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * CRSF for Arduino is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with CRSF for Arduino. If not, see .
- *
- */
-
-/* The Arduino IDE links main_rc.cpp to any sketch that uses the CRSFforArduino library.
- * EG When you open the "RC Channels" example sketch, the Arduino IDE will link main_rc.cpp to it.
- * To work around this, preprocessor directives are used to exclude the main_rc.cpp code from your sketch.
- */
-#if defined(ARDUINO) && defined(PLATFORMIO)
-#include "Arduino.h"
-
-#include "CRSFforArduino.hpp"
-
-CRSFforArduino crsf = CRSFforArduino(&Serial1);
-
-void setup()
-{
- // Initialize the serial port & wait for the port to open.
- Serial.begin(115200);
- while (!Serial)
- {
- ;
- }
-
- Serial.println("RC Channels Example");
-
- // Initialize the CRSFforArduino library.
- if (!crsf.begin())
- {
- Serial.println("CRSF for Arduino initialization failed!");
- while (1)
- {
- ;
- }
- }
-
- // Show the user that the sketch is ready.
- Serial.println("Ready");
- delay(1000);
-}
-
-void loop()
-{
- crsf.update();
-
- /* Print RC channels every 100 ms. Do this using the millis() function to avoid blocking the main loop. */
- static unsigned long lastPrint = 0;
- if (millis() - lastPrint >= 100)
- {
- lastPrint = millis();
- Serial.print("RC Channels ");
- }
-}
-#endif // defined(ARDUINO) && defined(PLATFORMIO)
diff --git a/examples/platformio/main_telemetry.cpp b/examples/platformio/main_telemetry.cpp
deleted file mode 100644
index b4c6fd17..00000000
--- a/examples/platformio/main_telemetry.cpp
+++ /dev/null
@@ -1,247 +0,0 @@
-/**
- * @file main_telemetry.cpp
- * @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief This file demonstrates how to use CRSF for Arduino to send telemetry to your RC transmitter using the CRSF protocol.
- * @version 1.0.0
- * @date 2024-1-20
- *
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
- *
- * @section License GNU General Public License v3.0
- * This main file is a part of the CRSF for Arduino library.
- * CRSF for Arduino is free software: you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * CRSF for Arduino is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with CRSF for Arduino. If not, see .
- *
- */
-
-/* The Arduino IDE links main_telemetry.cpp to any sketch that uses the CRSFforArduino library.
-EG When you open the "telemetry.ino" example sketch, the Arduino IDE will link main_telemetry.cpp to it.
-To work around this, preprocessor directives are used to exclude the main_telemetry.cpp code from your sketch. */
-#if defined(ARDUINO) && defined(PLATFORMIO)
-#include "Arduino.h"
-
-#include "CRSFforArduino.hpp"
-
-/* Configuration Options. */
-#define VIEW_RC_CHANNELS 0 // Set VIEW_RC_CHANNELS to 1 to view the RC channel data in the serial monitor.
-#define GENERATE_RANDOM_BATTERY_DATA 0 // Set GENERATE_RANDOM_BATTERY_DATA to 1 to generate random battery sensor telemetry data.
-#define GENERATE_RANDOM_GPS_DATA 0 // Set GENERATE_RANDOM_GPS_DATA to 1 to generate random GPS telemetry data.
-
-uint32_t timeNow = 0;
-
-/* Initialise the attitude telemetry with default values. */
-int16_t roll = -200; // Roll is in decided degrees (eg -200 = -20.0 degrees).
-int16_t pitch = 150; // Pitch is in decided degrees (eg 150 = 15.0 degrees).
-uint16_t yaw = 2758; // Yaw is in decided degrees (eg 2758 = 275.8 degrees).
-
-/* Initialise the barometric altitude telemetry with default values. */
-uint16_t baroAltitude = 10; // Barometric altitude is in decimetres (eg 10 = 1.0 metres).
-int16_t verticalSpeed = 50; // Vertical speed is in centimetres per second (eg 50 = 0.5 metres per second).
-
-/* Initialise the battery sensor telemetry with default values. */
-float batteryVoltage = 385.0F; // Battery voltage is in millivolts (mV * 100).
-float batteryCurrent = 150.0F; // Battery current is in milliamps (mA * 10).
-uint32_t batteryFuel = 700; // Battery fuel is in milliamp hours (mAh).
-uint8_t batteryPercent = 50; // Battery percentage remaining is in percent (0 - 100).
-
-/* Initialise the GPS telemetry data with default values. */
-float latitude = -41.18219482686493F; // Latitude is in decimal degrees.
-float longitude = 174.9497131419602F; // Longitude is in decimal degrees.
-float altitude = 100.0F; // Altitude is in centimetres.
-float speed = 500.0F; // Speed is in cm/s
-float groundCourse = 275.8F; // Ground Course is in degrees.
-uint8_t satellites = 7; // 7 satellites are in view (implies a 3D fix).
-
-CRSFforArduino crsf = CRSFforArduino(&Serial1);
-
-#if VIEW_RC_CHANNELS > 0
-const int channelCount = 8;
-const char *channelNames[crsfProtocol::RC_CHANNEL_COUNT] = {
- "A", "E", "T", "R", "Aux1", "Aux2", "Aux3", "Aux4", "Aux5", "Aux6", "Aux7", "Aux8", "Aux9", "Aux10", "Aux11", "Aux12"};
-
-static_assert(channelCount <= crsfProtocol::RC_CHANNEL_COUNT, "The number of RC channels must be less than or equal to the maximum number of RC channels supported by CRSF.");
-#endif
-
-void setup()
-{
-#if VIEW_RC_CHANNELS > 0 || defined(CRSF_DEBUG)
- Serial.begin(115200);
- while (!Serial)
- {
- ;
- }
-
- Serial.println("GPS Telemetry Example");
-#endif
-
- /* Initialise CRSF for Arduino */
- if (!crsf.begin())
- {
-#if VIEW_RC_CHANNELS > 0 || defined(CRSF_DEBUG)
- Serial.println("CRSF for Arduino initialization failed!");
-#endif
- while (1)
- {
- ;
- }
- }
-
-#if VIEW_RC_CHANNELS > 0 || defined(CRSF_DEBUG)
- /* Show the user that the sketch is ready. */
- Serial.println("Ready");
- delay(1000);
-#endif
-}
-
-void loop()
-{
-
- // Use timeNow to store the current time in milliseconds.
- timeNow = millis();
-
- /* Attitude Telemetry
-
- Normally, you would read the raw attitude data from your IMU and convert it to roll, pitch and yaw values.
- For the purposes of this example, we will just update the following with random values:
- - Roll
- - Pitch
- - Yaw
-
- These values are updated at a rate of 100 Hz.
- */
-
- /* Update the attitude telemetry at a rate of 100 Hz. */
- static unsigned long lastAttitudeUpdate = 0;
- if (timeNow - lastAttitudeUpdate >= 10)
- {
- lastAttitudeUpdate = timeNow;
-
- /* Update the attitude telemetry with the new values. */
- crsf.telemetryWriteAttitude(roll, pitch, yaw);
- }
-
- /* Barometric Altitude Telemetry
-
- Normally, you would read the barometric altitude and vertical speed from a barometric pressure sensor
- connected to your Arduino board.
-
- For the purposes of this example, we will just update the following with random values:
- - Barometric Altitude
- - Vertical Speed
-
- These values are updated at a rate of 10 Hz.
- */
-
- /* Update the barometric altitude telemetry at a rate of 10 Hz. */
- static unsigned long lastBaroAltitudeUpdate = 0;
- if (timeNow - lastBaroAltitudeUpdate >= 100)
- {
- lastBaroAltitudeUpdate = timeNow;
-
- /* Update the barometric altitude telemetry with the new values. */
- crsf.telemetryWriteBaroAltitude(baroAltitude, verticalSpeed);
- }
-
- /* Battery Telemetry
-
- Normally, you read the battery voltage and current from two analog pins on your Arduino board or from a
- battery sensor connected to your Arduino board.
- For the purposes of this example, we will just update the following with random values:
- - Battery Voltage
- - Battery Current
-
- These values are updated at a rate of 10 Hz.
- Battery fuel and percentage remaining are calculated from the battery voltage and current values, with
- a simulated battery capacity of 1000 mAh. */
-
- /* Update the battery sensor telemetry at a rate of 10 Hz. */
- static unsigned long lastBatteryUpdate = 0;
- if (timeNow - lastBatteryUpdate >= 100)
- {
- lastBatteryUpdate = timeNow;
-
-#if GENERATE_RANDOM_BATTERY_DATA > 0
- // Generate random values for the battery sensor telemetry.
- batteryVoltage = random(300, 420);
- batteryCurrent = random(0, 1000);
-#endif
-
- // Calculate the battery fuel and percentage remaining.
- // batteryFuel = (uint32_t)(batteryFuel + (batteryCurrent / 36000));
- // batteryPercent = (uint8_t)(batteryFuel / 10);
-
- // Update the battery sensor telemetry with the new values.
- crsf.telemetryWriteBattery(batteryVoltage, batteryCurrent, batteryFuel, batteryPercent);
- }
-
- /* GPS Telemetry
-
- Normally, you would update the GPS telemetry data with the latest values from your GPS module.
- For the purposes of this example, we will just update the following with random values:
- - Latitude
- - Longitude
- - Altitude
- - Speed
- - Ground Course
- - Satellites
-
- These values are updated at a rate of 1 Hz.
- Normally, you would update these values at a rate of 5 Hz or higher.
- */
-
- /* Update the GPS telemetry data at a rate of 1 Hz. */
- static unsigned long lastGpsUpdate = 0;
- if (timeNow - lastGpsUpdate >= 1000)
- {
- lastGpsUpdate = timeNow;
-
-#if GENERATE_RANDOM_GPS_DATA > 0
- // Generate random values for the GPS telemetry data.
- latitude = random(-90, 90);
- longitude = random(-180, 180);
- altitude = random(0, 500000);
- speed = random(0, 6625);
- groundCourse = random(0, 359);
- satellites = random(0, 16);
-#endif
-
- // Update the GPS telemetry data with the new values.
- crsf.telemetryWriteGPS(latitude, longitude, altitude, speed, groundCourse, satellites);
- }
-
- /* Call crsf.update() in the main loop to process CRSF packets. */
- crsf.update();
-
-/* You can process RC channel data here. */
-#if VIEW_RC_CHANNELS > 0
- static unsigned long lastPrint = 0;
- if (timeNow - lastPrint >= 100)
- {
- lastPrint = timeNow;
- Serial.print("RC Channels <");
- for (uint8_t i = 0; i < channelCount; i++)
- {
- Serial.print(channelNames[i]);
- Serial.print(": ");
- Serial.print(crsf.rcToUs(crsf.getChannel(i + 1)));
- if (i < channelCount - 1)
- {
- Serial.print(", ");
- }
- }
- Serial.println(">");
- }
-#endif
-}
-
-#endif // defined(ARDUINO) && defined(PLATFORMIO)
diff --git a/examples/rc_channels/rc_channels.ino b/examples/rc_channels/rc_channels.ino
new file mode 100644
index 00000000..c67a7de3
--- /dev/null
+++ b/examples/rc_channels/rc_channels.ino
@@ -0,0 +1,138 @@
+/**
+ * @file rc_channels.ino
+ * @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
+ * @brief Example of how to read rc channels from a receiver.
+ * @version 1.0.0
+ * @date 2024-2-9
+ *
+ * @copyright Copyright (c) 2024, Cassandra "ZZ Cat" Robinson. All rights reserved.
+ *
+ * @section License GNU General Public License v3.0
+ * This example is a part of the CRSF for Arduino library.
+ * CRSF for Arduino is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * CRSF for Arduino is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with CRSF for Arduino. If not, see .
+ *
+ */
+
+#include "CRSFforArduino.hpp"
+#define USE_SERIAL_PLOTTER 0
+
+CRSFforArduino *crsf = nullptr;
+
+int rcChannelCount = crsfProtocol::RC_CHANNEL_COUNT;
+const char *rcChannelNames[] = {
+ "A",
+ "E",
+ "T",
+ "R",
+ "Aux1",
+ "Aux2",
+ "Aux3",
+ "Aux4",
+
+ "Aux5",
+ "Aux6",
+ "Aux7",
+ "Aux8",
+ "Aux9",
+ "Aux10",
+ "Aux11",
+ "Aux12"};
+
+void onReceiveRcChannels(serialReceiverLayer::rcChannels_t *rcChannels);
+
+void setup()
+{
+ // Initialise the serial port & wait for the port to open.
+ Serial.begin(115200);
+ while (!Serial)
+ {
+ ;
+ }
+
+ // Initialise CRSF for Arduino.
+ crsf = new CRSFforArduino();
+ if (!crsf->begin())
+ {
+ crsf->end();
+
+ delete crsf;
+ crsf = nullptr;
+
+ Serial.println("CRSF for Arduino initialisation failed!");
+ while (1)
+ {
+ delay(10);
+ }
+ }
+
+ rcChannelCount = rcChannelCount > crsfProtocol::RC_CHANNEL_COUNT ? crsfProtocol::RC_CHANNEL_COUNT : rcChannelCount;
+
+ crsf->setRcChannelsCallback(onReceiveRcChannels);
+
+ // Show the user that the sketch is ready.
+ Serial.println("RC Channels Example");
+ delay(1000);
+ Serial.println("Ready");
+ delay(1000);
+}
+
+void loop()
+{
+ crsf->update();
+}
+
+void onReceiveRcChannels(serialReceiverLayer::rcChannels_t *rcChannels)
+{
+ if (rcChannels->failsafe == false)
+ {
+ /* Print RC channels every 100 ms. */
+ unsigned long thisTime = millis();
+ static unsigned long lastTime = millis();
+
+ /* Compensate for millis() overflow. */
+ if (thisTime < lastTime)
+ {
+ lastTime = thisTime;
+ }
+
+ if (thisTime - lastTime >= 100)
+ {
+ lastTime = thisTime;
+#if USE_SERIAL_PLOTTER > 0
+ for (int i = 1; i <= rcChannelCount; i++)
+ {
+ Serial.print(i);
+ Serial.print(":");
+ Serial.print(crsf->rcToUs(crsf->getChannel(i)));
+ Serial.print("\t");
+ }
+ Serial.println();
+#else
+ Serial.print("RC Channels <");
+ for (int i = 1; i <= rcChannelCount; i++)
+ {
+ Serial.print(rcChannelNames[i - 1]);
+ Serial.print(": ");
+ Serial.print(crsf->rcToUs(crsf->getChannel(i)));
+
+ if (i < rcChannelCount)
+ {
+ Serial.print(", ");
+ }
+ }
+ Serial.println(">");
+#endif
+ }
+ }
+}
diff --git a/examples/telemetry/telemetry.ino b/examples/telemetry/telemetry.ino
index 42418d8a..df70a228 100644
--- a/examples/telemetry/telemetry.ino
+++ b/examples/telemetry/telemetry.ino
@@ -1,14 +1,14 @@
/**
- * @file telemetry.ino
+ * @file flight_modes.ino
* @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief This demonstrates how to use CRSF for Arduino to send telemetry to your RC transmitter using the CRSF protocol.
+ * @brief Example of how to send telemetry back to your RC handset using CRSF for Arduino.
* @version 1.0.0
- * @date 2024-1-20
- *
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
+ * @date 2024-2-9
+ *
+ * @copyright Copyright (c) 2024, Cassandra "ZZ Cat" Robinson. All rights reserved.
*
* @section License GNU General Public License v3.0
- * This example sketch is a part of the CRSF for Arduino library.
+ * This example is a part of the CRSF for Arduino library.
* CRSF for Arduino is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
@@ -24,15 +24,10 @@
*
*/
-#if defined(ARDUINO) && defined(PLATFORMIO)
-#error "This example sketch is not compatible with PlatformIO. Please use the main_gps-telemetry.cpp example instead."
-#elif defined(ARDUINO) && !defined(PLATFORMIO)
-
#include "CRSFforArduino.hpp"
/* Configuration Options. */
#define VIEW_RC_CHANNELS 0 // Set VIEW_RC_CHANNELS to 1 to view the RC channel data in the serial monitor.
-#define USE_SERIAL_PLOTTER 1 // Set USE_SERIAL_PLOTTER to 1 to view this example's data in the Arduino IDE's serial plotter.
#define GENERATE_RANDOM_BATTERY_DATA 0 // Set GENERATE_RANDOM_BATTERY_DATA to 1 to generate random battery sensor telemetry data.
#define GENERATE_RANDOM_GPS_DATA 0 // Set GENERATE_RANDOM_GPS_DATA to 1 to generate random GPS telemetry data.
@@ -59,39 +54,34 @@ float longitude = 174.9497131419602F; // Longitude is in decimal degrees.
float altitude = 100.0F; // Altitude is in centimetres.
float speed = 500.0F; // Speed is in cm/s
float groundCourse = 275.8F; // Ground Course is in degrees.
-uint8_t satellites = 4;
-
-const int channelCount = crsfProtocol::RC_CHANNEL_COUNT; // I'm not sure if this is right, but we can always manually put in the number of channels desired
-
-/* The CRSF Protocol only supports up to 16 proportional RC channels.
-So, an assert is needed to prevent channelCount from being set to any arbitary number that is higher than 16. */
-static_assert(channelCount <= crsfProtocol::RC_CHANNEL_COUNT, "The number of RC channels must be less than or equal to the maximum number of RC channels supported by CRSF.");
+uint8_t satellites = 7; // 7 satellites are in view (implies a 3D fix).
CRSFforArduino crsf = CRSFforArduino(&Serial1);
-#if USE_SERIAL_PLOTTER == 0 && VIEW_RC_CHANNELS > 0
+#if VIEW_RC_CHANNELS > 0
+const int channelCount = 8;
const char *channelNames[crsfProtocol::RC_CHANNEL_COUNT] = {
"A", "E", "T", "R", "Aux1", "Aux2", "Aux3", "Aux4", "Aux5", "Aux6", "Aux7", "Aux8", "Aux9", "Aux10", "Aux11", "Aux12"};
+
+static_assert(channelCount <= crsfProtocol::RC_CHANNEL_COUNT, "The number of RC channels must be less than or equal to the maximum number of RC channels supported by CRSF.");
#endif
void setup()
{
-#if VIEW_RC_CHANNELS > 0 || defined(CRSF_DEBUG) || USE_SERIAL_PLOTTER > 0
+#if VIEW_RC_CHANNELS > 0 || defined(CRSF_DEBUG)
Serial.begin(115200);
while (!Serial)
{
;
}
-#if USE_SERIAL_PLOTTER == 0
Serial.println("GPS Telemetry Example");
-#endif
#endif
/* Initialise CRSF for Arduino */
if (!crsf.begin())
{
-#if (VIEW_RC_CHANNELS > 0 || defined(CRSF_DEBUG)) && USE_SERIAL_PLOTTER == 0
+#if VIEW_RC_CHANNELS > 0 || defined(CRSF_DEBUG)
Serial.println("CRSF for Arduino initialization failed!");
#endif
while (1)
@@ -100,7 +90,7 @@ void setup()
}
}
-#if (VIEW_RC_CHANNELS > 0 || defined(CRSF_DEBUG)) && USE_SERIAL_PLOTTER == 0
+#if VIEW_RC_CHANNELS > 0 || defined(CRSF_DEBUG)
/* Show the user that the sketch is ready. */
Serial.println("Ready");
delay(1000);
@@ -217,22 +207,6 @@ void loop()
speed = random(0, 6625);
groundCourse = random(0, 359);
satellites = random(0, 16);
-
-#if USE_SERIAL_PLOTTER > 0
- Serial.print("Lat:");
- Serial.print(latitude);
- Serial.print("\tLon:");
- Serial.print(longitude);
- Serial.print("\tAlt:");
- Serial.print(altitude);
- Serial.print("\tSpeed:");
- Serial.print(speed);
- Serial.print("\tGroundCourse:");
- Serial.print(groundCourse);
- Serial.print("\tSatellites:");
- Serial.print(satellites);
- Serial.println();
-#endif
#endif
// Update the GPS telemetry data with the new values.
@@ -248,17 +222,6 @@ void loop()
if (timeNow - lastPrint >= 100)
{
lastPrint = timeNow;
-#if USE_SERIAL_PLOTTER == 0
- for (int i = 1; i <= channelCount; i++)
- {
- //Serial.print("Channel");
- Serial.print(i);
- Serial.print(":");
- Serial.print(crsf.rcToUs(crsf.getChannel(i)));
- Serial.print("\t");
- }
- Serial.println();
-#else
Serial.print("RC Channels <");
for (uint8_t i = 0; i < channelCount; i++)
{
@@ -271,9 +234,6 @@ void loop()
}
}
Serial.println(">");
-#endif
}
#endif
}
-
-#endif // defined(ARDUINO) && defined(PLATFORMIO)
diff --git a/library.json b/library.json
new file mode 100644
index 00000000..c887830c
--- /dev/null
+++ b/library.json
@@ -0,0 +1,33 @@
+{
+ "$schema": "https://raw.githubusercontent.com/platformio/platformio-core/develop/platformio/assets/schema/library.json",
+ "name": "CRSFforArduino",
+ "version": "1.0.0",
+ "description": "An Arduino Library for communicating with ExpressLRS and TBS Crossfire receivers.",
+ "keywords": "arduino, remote-control, arduino-library, protocols, rc, radio-control, crsf, expresslrs",
+ "repository":
+ {
+ "type": "git",
+ "url": "https://github.com/ZZ-Cat/CRSFforArduino.git"
+ },
+ "authors":
+ [
+ {
+ "name": "Cassandra Robinson",
+ "email": "nicad.heli.flier@gmail.com",
+ "url": "https://github.com/ZZ-Cat",
+ "maintainer": true
+ }
+ ],
+ "license": "GNU GPLv3",
+ "homepage": "https://github.com/ZZ-Cat/CRSFforArduino",
+ "dependencies": {
+ },
+ "frameworks": "Arduino",
+ "platforms": [
+ "atmelsam",
+ "espressif32",
+ "teensy"
+ ],
+ "examples": [
+ ]
+ }
diff --git a/library.properties b/library.properties
index df32d0ac..4e9dde0a 100644
--- a/library.properties
+++ b/library.properties
@@ -8,4 +8,4 @@ category=Communication
url=https://github.com/ZZ-Cat/CRSFforArduino
depends=Adafruit Zero DMA Library
dot_a_linkage=false
-includes=CRSFforArduino.h
+includes=CRSFforArduino.hpp
diff --git a/platformio.ini b/platformio.ini
index 50c93ee1..c8b01bf3 100644
--- a/platformio.ini
+++ b/platformio.ini
@@ -1,18 +1,30 @@
+; 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
+
[platformio]
+core_dir = .pio/core
+; default_envs = development
extra_configs =
targets/common.ini
- targets/adafruit_unified_esp32.ini
- targets/adafruit_unified_samd21.ini
- targets/adafruit_unified_samd51.ini
- targets/arduino_unified_esp32.ini
- targets/arduino_unified_samd21.ini
- targets/espressif_unified_esp32.ini
- targets/seeed_studio_esp32.ini
- targets/seeed_studio_samd21.ini
- targets/sparkfun_unified_esp32.ini
- targets/teensy_unified.ini
-core_dir = .pio/core
-include_dir = src/platformio/include
+ targets/unified_esp32.ini
+ targets/unified_rp2040.ini
+ targets/unified_samd21.ini
+ targets/unified_samd51.ini
+ targets/unified_teensy3x.ini
+ targets/unified_teensy4x.ini
+include_dir = src
lib_dir = src
-src_dir = examples/platformio
-test_dir = src/platformio/test
+src_dir = src
+test_dir =
+
+; [env:development]
+; board = adafruit_metro_m4
+; build_type = debug
+; platform = atmelsam@8.2.0
diff --git a/src/CRSFforArduino/src/CFA_Config.hpp b/src/CFA_Config.hpp
similarity index 89%
rename from src/CRSFforArduino/src/CFA_Config.hpp
rename to src/CFA_Config.hpp
index f744c25f..bd62254f 100644
--- a/src/CRSFforArduino/src/CFA_Config.hpp
+++ b/src/CFA_Config.hpp
@@ -3,9 +3,9 @@
* @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
* @brief This is the configuration file for CRSF for Arduino.
* @version 1.0.0
- * @date 2024-1-20
+ * @date 2024-2-9
*
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
+ * @copyright Copyright (c) 2024, Cassandra "ZZ Cat" Robinson. All rights reserved.
*
* @section License GNU General Public License v3.0
* This header file is a part of the CRSF for Arduino library.
@@ -26,7 +26,7 @@
#pragma once
-#include
+#include "Arduino.h"
/* The following defines are used to configure CRSF for Arduino.
You can change these values to suit your needs. */
@@ -37,11 +37,19 @@ namespace crsfForArduinoConfig
Versioning is done using Semantic Versioning 2.0.0.
See https://semver.org/ for more information. */
#define CRSFFORARDUINO_VERSION "1.0.0"
-#define CRSFFORARDUINO_VERSION_DATE "2024-1-20"
+#define CRSFFORARDUINO_VERSION_DATE "2024-2-9"
#define CRSFFORARDUINO_VERSION_MAJOR 1
#define CRSFFORARDUINO_VERSION_MINOR 0
#define CRSFFORARDUINO_VERSION_PATCH 0
+/* Failsafe Options
+- CRSF_FAILSAFE_LQI_THRESHOLD: The minimum LQI value for the receiver to be considered connected.
+- CRSF_FAILSAFE_RSSI_THRESHOLD: The minimum RSSI value for the receiver to be considered connected.
+ - NB: It is considered good practice to set this value to the same as the RSSI Sensitivity Limit in your Lua script.
+*/
+#define CRSF_FAILSAFE_LQI_THRESHOLD 80
+#define CRSF_FAILSAFE_RSSI_THRESHOLD 105
+
/* RC Options
- RC_ENABLED: Enables or disables the RC API.
- RC_MAX_CHANNELS: The maximum number of RC channels to be received.
@@ -84,6 +92,8 @@ information back to your controller. */
#define CRSF_TELEMETRY_FLIGHTMODE_ENABLED 0
#define CRSF_TELEMETRY_GPS_ENABLED 1
+#define CRSF_LINK_STATISTICS_ENABLED 1
+
/* Debug Options
- DEBUG_ENABLED: Enables or disables debug output over the selected serial port.
- CRSF_DEBUG_SERIAL_PORT: The serial port to use for debug output. Usually the native USB port.
diff --git a/src/CRSFforArduino/src/CRSFforArduino.cpp b/src/CRSFforArduino.cpp
similarity index 87%
rename from src/CRSFforArduino/src/CRSFforArduino.cpp
rename to src/CRSFforArduino.cpp
index 4524ae99..f5284b16 100644
--- a/src/CRSFforArduino/src/CRSFforArduino.cpp
+++ b/src/CRSFforArduino.cpp
@@ -1,11 +1,12 @@
/**
* @file CRSFforArduino.cpp
* @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief CRSF for Arduino facilitates the use of ExpressLRS RC receivers in Arduino projects.
+ * @brief This is the Sketch Layer, which is a simplified API for CRSF for Arduino.
+ * It is intended to be used by the user in their sketches.
* @version 1.0.0
- * @date 2024-1-20
+ * @date 2024-2-9
*
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
+ * @copyright Copyright (c) 2024, Cassandra "ZZ Cat" Robinson. All rights reserved.
*
* @section License GNU General Public License v3.0
* This source file is a part of the CRSF for Arduino library.
@@ -21,10 +22,11 @@
*
* You should have received a copy of the GNU General Public License
* along with CRSF for Arduino. If not, see .
- *
+ *
*/
#include "CRSFforArduino.hpp"
+#include "Arduino.h"
namespace sketchLayer
{
@@ -116,7 +118,7 @@ namespace sketchLayer
*
* @return The RC value.
*/
- uint16_t CRSFforArduino::readRcChannel(uint8_t channel, bool raw)
+ [[deprecated("Use RC channel callback instead")]] uint16_t CRSFforArduino::readRcChannel(uint8_t channel, bool raw)
{
#if CRSF_RC_ENABLED > 0
return _serialReceiver->readRcChannel(channel - 1, raw);
@@ -136,7 +138,7 @@ namespace sketchLayer
* @param channel The channel to read.
* @return The RC value.
*/
- uint16_t CRSFforArduino::getChannel(uint8_t channel)
+ [[deprecated("Use RC channel callback instead")]] uint16_t CRSFforArduino::getChannel(uint8_t channel)
{
#if CRSF_RC_ENABLED > 0
return _serialReceiver->getChannel(channel - 1);
@@ -168,6 +170,26 @@ namespace sketchLayer
#endif
}
+ void CRSFforArduino::setRcChannelsCallback(void (*callback)(serialReceiverLayer::rcChannels_t *rcChannels))
+ {
+#if CRSF_RC_ENABLED > 0
+ _serialReceiver->setRcChannelsCallback(callback);
+#else
+ // Prevent compiler warnings
+ (void)callback;
+#endif
+ }
+
+ void CRSFforArduino::setLinkStatisticsCallback(void (*callback)(serialReceiverLayer::link_statistics_t linkStatistics))
+ {
+#if CRSF_LINK_STATISTICS_ENABLED > 0
+ _serialReceiver->setLinkStatisticsCallback(callback);
+#else
+ // Prevent compiler warnings
+ (void)callback;
+#endif
+ }
+
/**
* @brief Assigns a Flight Mode to the specified channel.
*
@@ -177,7 +199,7 @@ namespace sketchLayer
* @param max The maximum RC value for the Flight Mode to be active.
* @return true if the Flight Mode was assigned successfully.
*/
- bool CRSFforArduino::setFlightMode(serialReceiver::flightModeId_t flightMode, uint8_t channel, uint16_t min, uint16_t max)
+ bool CRSFforArduino::setFlightMode(serialReceiverLayer::flightModeId_t flightMode, uint8_t channel, uint16_t min, uint16_t max)
{
#if CRSF_RC_ENABLED > 0 && CRSF_FLIGHTMODES_ENABLED > 0
return _serialReceiver->setFlightMode(flightMode, channel - 1, _serialReceiver->usToRc(min), _serialReceiver->usToRc(max));
@@ -198,7 +220,7 @@ namespace sketchLayer
* This is called when the RC value for the Flight Mode channel is between the min and max values.
* @param callback The callback function to register.
*/
- void CRSFforArduino::setFlightModeCallback(void (*callback)(serialReceiver::flightModeId_t flightMode))
+ void CRSFforArduino::setFlightModeCallback(void (*callback)(serialReceiverLayer::flightModeId_t flightMode))
{
#if CRSF_RC_ENABLED > 0 && CRSF_FLIGHTMODES_ENABLED > 0
_serialReceiver->setFlightModeCallback(callback);
@@ -270,7 +292,7 @@ namespace sketchLayer
*
* @param flightMode The Flight Mode to send.
*/
- void CRSFforArduino::telemetryWriteFlightMode(serialReceiver::flightModeId_t flightMode)
+ void CRSFforArduino::telemetryWriteFlightMode(serialReceiverLayer::flightModeId_t flightMode)
{
#if CRSF_TELEMETRY_ENABLED > 0 && CRSF_TELEMETRY_FLIGHTMODE_ENABLED > 0
_serialReceiver->telemetryWriteFlightMode(flightMode);
diff --git a/src/CRSFforArduino.hpp b/src/CRSFforArduino.hpp
index 83a32446..1a29c362 100644
--- a/src/CRSFforArduino.hpp
+++ b/src/CRSFforArduino.hpp
@@ -1,11 +1,12 @@
/**
- * @file CRSFforArduino.hpp
+ * @file CRSFforArduino.cpp
* @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief Top level header for CRSF for Arduino, to help with Arduino IDE compatibility.
+ * @brief This is the Sketch Layer, which is a simplified API for CRSF for Arduino.
+ * It is intended to be used by the user in their sketches.
* @version 1.0.0
- * @date 2024-1-20
+ * @date 2024-2-9
*
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
+ * @copyright Copyright (c) 2024, Cassandra "ZZ Cat" Robinson. All rights reserved.
*
* @section License GNU General Public License v3.0
* This header file is a part of the CRSF for Arduino library.
@@ -26,4 +27,44 @@
#pragma once
-#include "CRSFforArduino/src/CRSFforArduino.hpp"
+#include "Arduino.h"
+#include "SerialReceiver/SerialReceiver.hpp"
+
+namespace sketchLayer
+{
+ class CRSFforArduino : private serialReceiverLayer::SerialReceiver
+ {
+ public:
+ CRSFforArduino();
+ CRSFforArduino(HardwareSerial *serialPort);
+ ~CRSFforArduino();
+ bool begin();
+ void end();
+ void update();
+
+ // RC channel functions.
+ uint16_t getChannel(uint8_t channel);
+ uint16_t rcToUs(uint16_t rc);
+ uint16_t readRcChannel(uint8_t channel, bool raw = false);
+ void setRcChannelsCallback(void (*callback)(serialReceiverLayer::rcChannels_t *rcChannels));
+
+ // Link statistics functions.
+ void setLinkStatisticsCallback(void (*callback)(serialReceiverLayer::link_statistics_t linkStatistics));
+
+ // Flight mode functions.
+ bool setFlightMode(serialReceiverLayer::flightModeId_t flightMode, uint8_t channel, uint16_t min, uint16_t max);
+ void setFlightModeCallback(void (*callback)(serialReceiverLayer::flightModeId_t flightMode));
+
+ // Telemetry functions.
+ void telemetryWriteAttitude(int16_t roll, int16_t pitch, int16_t yaw);
+ void telemetryWriteBaroAltitude(uint16_t altitude, int16_t vario);
+ void telemetryWriteBattery(float voltage, float current, uint32_t fuel, uint8_t percent);
+ void telemetryWriteFlightMode(serialReceiverLayer::flightModeId_t flightMode);
+ void telemetryWriteGPS(float latitude, float longitude, float altitude, float speed, float groundCourse, uint8_t satellites);
+
+ private:
+ SerialReceiver *_serialReceiver;
+ };
+} // namespace sketchLayer
+
+using namespace sketchLayer;
diff --git a/src/CRSFforArduino/library.json b/src/CRSFforArduino/library.json
deleted file mode 100644
index 935527a9..00000000
--- a/src/CRSFforArduino/library.json
+++ /dev/null
@@ -1,46 +0,0 @@
-{
- "$schema": "https://raw.githubusercontent.com/platformio/platformio-core/develop/platformio/assets/schema/library.json",
- "name": "CRSFforArduino",
- "version": "1.0.0",
- "description": "Arduino library for Crossfire protocol",
- "keywords": [
- "adafruit",
- "arduino",
- "communication",
- "crossfire",
- "crsf",
- "elrs",
- "expresslrs",
- "tbs",
- "telemetry",
- "protocol",
- "remote control",
- "rc"
- ],
- "repository":
- {
- "type": "git",
- "url": "https://github.com/ZZ-Cat/CRSFforArduino"
- },
- "authors": [
- {
- "name": "Cassandra \"ZZ Cat\" Robinson",
- "email": "nicad.heli.flier@gmail.com",
- "maintainer": true
- }
- ],
- "license": "GPL-3.0-or-later",
- "frameworks": "arduino",
- "platforms": [
- "atmelsam",
- "espressif32",
- "teensy"
- ],
- "headers": [
- "Arduino.h",
- "CRSFforArduino.h"
- ],
- "dependencies":
- {
- }
-}
diff --git a/src/CRSFforArduino/src/CRSFforArduino.hpp b/src/CRSFforArduino/src/CRSFforArduino.hpp
deleted file mode 100644
index 97521a9d..00000000
--- a/src/CRSFforArduino/src/CRSFforArduino.hpp
+++ /dev/null
@@ -1,70 +0,0 @@
-/**
- * @file CRSFforArduino.hpp
- * @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief CRSF for Arduino facilitates the use of ExpressLRS RC receivers in Arduino projects.
- * @version 1.0.0
- * @date 2024-1-20
- *
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
- *
- * @section License GNU General Public License v3.0
- * This header file is a part of the CRSF for Arduino library.
- * CRSF for Arduino is free software: you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * CRSF for Arduino is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with CRSF for Arduino. If not, see .
- *
- */
-
-#pragma once
-
-#include "Arduino.h"
-
-// #if defined(ARDUINO) && defined(PLATFORMIO)
-#include "SerialReceiver/SerialReceiver.hpp"
-// #elif defined(ARDUINO) && !defined(PLATFORMIO)
-// #include "lib/CRSFforArduino/src/SerialReceiver/SerialReceiver.hpp"
-// #endif
-
-namespace sketchLayer
-{
- class CRSFforArduino : private serialReceiver::SerialReceiver
- {
- public:
- CRSFforArduino();
- CRSFforArduino(HardwareSerial *serialPort);
- ~CRSFforArduino();
- bool begin();
- void end();
- void update();
-
- // RC channel functions.
- uint16_t getChannel(uint8_t channel);
- uint16_t rcToUs(uint16_t rc);
- uint16_t readRcChannel(uint8_t channel, bool raw = false);
-
- // Flight mode functions.
- bool setFlightMode(serialReceiver::flightModeId_t flightMode, uint8_t channel, uint16_t min, uint16_t max);
- void setFlightModeCallback(void (*callback)(serialReceiver::flightModeId_t flightMode));
-
- // Telemetry functions.
- void telemetryWriteAttitude(int16_t roll, int16_t pitch, int16_t yaw);
- void telemetryWriteBaroAltitude(uint16_t altitude, int16_t vario);
- void telemetryWriteBattery(float voltage, float current, uint32_t fuel, uint8_t percent);
- void telemetryWriteFlightMode(serialReceiver::flightModeId_t flightMode);
- void telemetryWriteGPS(float latitude, float longitude, float altitude, float speed, float groundCourse, uint8_t satellites);
-
- private:
- SerialReceiver *_serialReceiver;
- };
-} // namespace sketchLayer
-
-using namespace sketchLayer;
diff --git a/src/CRSFforArduino/src/Hardware/Hardware.hpp b/src/CRSFforArduino/src/Hardware/Hardware.hpp
deleted file mode 100644
index b96ad56a..00000000
--- a/src/CRSFforArduino/src/Hardware/Hardware.hpp
+++ /dev/null
@@ -1,38 +0,0 @@
-/**
- * @file Hardware.hpp
- * @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief This file is the top level of the hardware abstraction layer.
- * @version 1.0.0
- * @date 2024-1-20
- *
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
- *
- * @section License GNU General Public License v3.0
- * This header file is a part of the CRSF for Arduino library.
- * CRSF for Arduino is free software: you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * CRSF for Arduino is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with CRSF for Arduino. If not, see .
- *
- */
-
-#pragma once
-
-#if defined(ARDUINO) && defined(PLATFORMIO)
-#include "CFA_Config.hpp"
-#elif defined(ARDUINO) && !defined(PLATFORMIO)
-#include "../CFA_Config.hpp"
-#endif
-#include "CompatibilityTable/CompatibilityTable.hpp"
-// #include "hw_uart/hw_uart.hpp"
-
-using namespace crsfForArduinoConfig;
-using namespace hal;
diff --git a/src/CRSFforArduino/src/Hardware/hw_uart/hw_uart.cpp b/src/CRSFforArduino/src/Hardware/hw_uart/hw_uart.cpp
deleted file mode 100644
index c1ff917f..00000000
--- a/src/CRSFforArduino/src/Hardware/hw_uart/hw_uart.cpp
+++ /dev/null
@@ -1,404 +0,0 @@
-/**
- * @file hw_uart.cpp
- * @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief This is the hw_uart implementation file. It is used to configure CRSF for Arduino for specific development boards.
- * @version 1.0.0
- * @date 2024-1-20
- *
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
- *
- * @section License GNU General Public License v3.0
- * This source file is a part of the CRSF for Arduino library.
- * CRSF for Arduino is free software: you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * CRSF for Arduino is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with CRSF for Arduino. If not, see .
- *
- */
-
-#include "hw_uart.hpp"
-
-namespace hal
-{
- // #if defined(USE_DMA)
- // #if defined(ARDUINO_ARCH_SAMD)
- // #define DMA_BUFFER_SIZE 64
-
- // Adafruit_ZeroDMA *dma_memcopy;
- // Adafruit_ZeroDMA *dma_memset;
-
- // DmacDescriptor *descriptor_memcopy;
- // DmacDescriptor *descriptor_memset;
-
- // volatile bool dma_memcopy_transfer_complete = false;
- // volatile bool dma_memset_transfer_complete = false;
-
- // void dma_callback(Adafruit_ZeroDMA *dma)
- // {
- // if (dma == dma_memcopy)
- // {
- // dma_memcopy_transfer_complete = true;
- // }
- // else if (dma == dma_memset)
- // {
- // dma_memset_transfer_complete = true;
- // }
- // }
- // #endif
- // #endif
-
- hw_uart::hw_uart()
- {
- _uart_port = nullptr;
- }
-
- hw_uart::hw_uart(HardwareSerial *uart_port)
- {
- if (uart_port != nullptr)
- {
- _uart_port = uart_port;
- }
- }
-
- hw_uart::~hw_uart()
- {
- _uart_port = nullptr;
- // #ifdef USE_DMA
- // #if defined(ARDUINO_ARCH_SAMD)
- // // If DMA memory was initialized, delete it.
- // if (dma_memcopy != nullptr)
- // {
- // delete dma_memcopy;
- // }
-
- // if (dma_memset != nullptr)
- // {
- // delete dma_memset;
- // }
- // #endif
- // #endif
- }
-
- void hw_uart::setUART(uint8_t port, uint8_t rx, uint8_t tx)
- {
- return;
- // #if defined(ARDUINO_ARCH_SAMD)
- // // If UART port was defined beforehand, delete it.
- // if (_uart_port != nullptr)
- // {
- // _uart_port->~Uart();
-
- // // Debug.
- // // Serial.println("[Development Board | DEBUG]: Deleted previous UART port.");
- // }
-
- // // Set the UART port.
- // switch (port)
- // {
- // case 0:
- // _uart_port = &Serial1;
-
- // // Debug.
- // // Serial.println("[Development Board | DEBUG]: Using Serial1.");
- // break;
-
- // case 1: // TO-DO: Fix this.
- // _uart_port = new Uart(&sercom2, rx, tx, SERCOM_RX_PAD_1, UART_TX_PAD_0);
-
- // // Debug.
- // // Serial.println("[Development Board | DEBUG]: Using Serial2.");
- // break;
-
- // default:
- // _uart_port = nullptr;
-
- // // Debug.
- // // Serial.println("[Development Board | ERROR]: No UART port was defined.");
- // break;
- // }
- // #elif defined(TEENSYDUINO)
- // // Default to Serial1 if Teensyduino is being used. May expand this in the future, if requested.
- // _uart_port = &Serial1;
-
- // // Debug.
- // // Serial.println("[Development Board | DEBUG]: Using Serial1.");
- // #elif defined(ARDUINO_ARCH_ESP32)
- // // Default to Serial1 if ESP32 is being used. May expand this in the future, if requested.
- // _uart_port = &Serial1;
-
- // // Debug.
- // // Serial.println("[Development Board | DEBUG]: Using Serial1.");
- // #else
- // _uart_port = nullptr;
-
- // // Debug.
- // // Serial.println("[Development Board | ERROR]: No UART port was defined.");
- // #endif
- }
-
- void hw_uart::clearUART()
- {
- return;
- // If UART port was defined beforehand, delete it.
- // if (_uart_port != nullptr)
- // {
- // #if not(defined(TEENSYDUINO) || defined(ARDUINO_ARCH_ESP32))
- // _uart_port->~Uart();
- // #endif
- // }
- }
-
- void hw_uart::begin(unsigned long baudrate, int config)
- {
- // Begin the UART port.
- _uart_port->begin(baudrate, config);
- }
-
- void hw_uart::end()
- {
- // End the UART port.
- _uart_port->end();
- }
-
- int hw_uart::available(void)
- {
- // Return the number of bytes available in the UART port.
- return _uart_port->available();
- }
-
- int hw_uart::peek(void)
- {
- // Return the next byte in the UART port without removing it from the buffer.
- return _uart_port->peek();
- }
-
- int hw_uart::read(void)
- {
- // Return the next byte in the UART port and remove it from the buffer.
- return _uart_port->read();
- }
-
- void hw_uart::flush(void)
- {
- // Flush the UART port.
- _uart_port->flush();
- }
-
- size_t hw_uart::write(uint8_t c)
- {
- // Write a byte to the UART port.
- return _uart_port->write(c);
- }
-
- size_t hw_uart::write(const uint8_t *buffer, size_t size)
- {
- // Write a buffer to the UART port.
- return _uart_port->write(buffer, size);
- }
-
- hw_uart::operator bool()
- {
- // Return if the UART port is available.
- return _uart_port->operator bool();
- }
-
- void hw_uart::enterCriticalSection()
- {
- // Enter a critical section.
-#if defined(ARDUINO_ARCH_SAMD)
- __disable_irq();
-#else
- noInterrupts();
-#endif
-
- // Increment the critical section counter.
- critical_section_counter++;
- }
-
- void hw_uart::exitCriticalSection()
- {
- // Decrement the critical section counter.
- critical_section_counter--;
-
- // Exit a critical section.
- if (critical_section_counter == 0)
- {
-#if defined(ARDUINO_ARCH_SAMD)
- __enable_irq();
-#else
- interrupts();
-#endif
- }
- }
-
- // #if defined(USE_DMA)
- // void hw_uart::memcpy_dma(void *dest, void *src, size_t size)
- // {
- // #if defined(ARDUINO_ARCH_SAMD)
- // // If DMA memory was not initialized, initialize it.
- // if (dma_memcopy == nullptr)
- // {
- // enterCriticalSection();
-
- // dma_memcopy = new Adafruit_ZeroDMA();
-
- // // Check if DMA memory was initialized.
- // if (dma_memcopy == nullptr)
- // {
- // exitCriticalSection();
- // return;
- // }
-
- // // Allocate DMA channel for memory & check if it was allocated.
- // if (dma_memcopy->allocate() != DMA_STATUS_OK)
- // {
- // delete dma_memcopy;
- // exitCriticalSection();
- // return;
- // }
-
- // // Allocate DMA descriptors for memory & check if they were allocated.
- // descriptor_memcopy = dma_memcopy->addDescriptor(
- // NULL, // No source data to start with.
- // NULL, // No destination to start with.
- // 0 // No data to start with.
- // );
-
- // if (descriptor_memcopy == nullptr)
- // {
- // delete dma_memcopy;
- // exitCriticalSection();
- // return;
- // }
-
- // // Set the DMA callback function.
- // dma_memcopy->setCallback(dma_callback);
-
- // // Set the DMA transfer complete flag.
- // dma_memcopy_transfer_complete = true;
-
- // exitCriticalSection();
- // }
-
- // // Check if the DMA transfer is complete.
- // if (dma_memcopy_transfer_complete == true)
- // {
- // // Reset the DMA transfer complete flag.
- // dma_memcopy_transfer_complete = false;
-
- // // Change the DMA descriptor.
- // dma_memcopy->changeDescriptor(
- // descriptor_memcopy,
- // src,
- // dest,
- // size);
-
- // // Start the DMA transfer.
- // if (dma_memcopy->startJob() == DMA_STATUS_OK)
- // {
- // dma_memcopy->trigger();
-
- // // Wait for the DMA transfer to complete.
- // while (dma_memcopy_transfer_complete == false)
- // {
- // ;
- // }
- // }
- // }
- // #else
- // // Default to memcpy if DMA is not supported.
- // memcpy(dest, src, size);
- // #endif
- // }
-
- // void hw_uart::memset_dma(void *dest, int value, size_t size)
- // {
- // #if defined(ARDUINO_ARCH_SAMD)
- // // If DMA memory was not initialized, initialize it.
- // if (dma_memset == nullptr)
- // {
- // enterCriticalSection();
-
- // dma_memset = new Adafruit_ZeroDMA();
-
- // // Check if DMA memory was initialized.
- // if (dma_memset == nullptr)
- // {
- // exitCriticalSection();
- // return;
- // }
-
- // // Allocate DMA channel for memory & check if it was allocated.
- // if (dma_memset->allocate() != DMA_STATUS_OK)
- // {
- // delete dma_memset;
- // exitCriticalSection();
- // return;
- // }
-
- // // Allocate DMA descriptors for memory & check if they were allocated.
- // descriptor_memset = dma_memset->addDescriptor(
- // NULL, // No source data to start with.
- // NULL, // No destination to start with.
- // 0, // No data to start with.
- // DMA_BEAT_SIZE_BYTE, // Transfer 1 byte at a time.
- // false, // Don't increment the source address.
- // true // Increment the destination address.
- // );
-
- // if (descriptor_memset == nullptr)
- // {
- // delete dma_memset;
- // exitCriticalSection();
- // return;
- // }
-
- // // Set the DMA callback function.
- // dma_memset->setCallback(dma_callback);
-
- // // Set the DMA transfer complete flag.
- // dma_memset_transfer_complete = true;
-
- // exitCriticalSection();
- // }
-
- // // Check if the DMA transfer is complete.
- // if (dma_memset_transfer_complete == true)
- // {
- // // Reset the DMA transfer complete flag.
- // dma_memset_transfer_complete = false;
-
- // // Change the DMA descriptor.
- // dma_memset->changeDescriptor(
- // descriptor_memset,
- // &value,
- // dest,
- // size);
-
- // // Start the DMA transfer.
- // if (dma_memset->startJob() == DMA_STATUS_OK)
- // {
- // dma_memset->trigger();
-
- // // Wait for the DMA transfer to complete.
- // while (dma_memset_transfer_complete == false)
- // {
- // ;
- // }
- // }
- // }
- // #else
- // // Default to memset if DMA is not supported.
- // memset(dest, value, size);
- // #endif
- // }
- // #endif
-} // namespace hal
diff --git a/src/CRSFforArduino/src/Hardware/hw_uart/hw_uart.hpp b/src/CRSFforArduino/src/Hardware/hw_uart/hw_uart.hpp
deleted file mode 100644
index 1b8bd450..00000000
--- a/src/CRSFforArduino/src/Hardware/hw_uart/hw_uart.hpp
+++ /dev/null
@@ -1,76 +0,0 @@
-/**
- * @file hw_uart.hpp
- * @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief This file contains the hw_uart class, which is used to configure CRSF for Arduino for specific development boards.
- * @version 1.0.0
- * @date 2024-1-20
- *
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
- *
- * @section License GNU General Public License v3.0
- * This header file is a part of the CRSF for Arduino library.
- * CRSF for Arduino is free software: you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * CRSF for Arduino is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with CRSF for Arduino. If not, see .
- *
- */
-
-#pragma once
-
-#include "Arduino.h"
-// #ifdef USE_DMA
-// #warning "DMA is enabled. This is an experimental feature and may not work as expected."
-// #if defined(ARDUINO_ARCH_SAMD)
-// #include "Adafruit_ZeroDMA.h"
-// #endif
-// #endif
-
-namespace hal
-{
- class hw_uart : private Stream
- {
- public:
- hw_uart();
- hw_uart(HardwareSerial *uart_port);
- virtual ~hw_uart();
-
- void setUART(uint8_t port, uint8_t rx, uint8_t tx);
- void clearUART();
-
- // Hardware Serial functions.
- void begin(unsigned long baudrate, int config = SERIAL_8N1);
- void end();
- int available(void);
- int peek(void);
- int read(void);
- void flush(void);
- size_t write(uint8_t c);
- size_t write(const uint8_t *buffer, size_t size);
- using Print::write; // pull in write(str) and write(buf, size) from Print
- operator bool();
-
- // Critical section functions.
- void enterCriticalSection();
- void exitCriticalSection();
-
- // #ifdef USE_DMA
- // // DMA functions.
- // void memcpy_dma(void *dest, void *src, size_t size);
- // void memset_dma(void *dest, int value, size_t size);
- // #endif
-
- private:
- uint16_t critical_section_counter = 0;
-
- HardwareSerial *_uart_port;
- };
-} // namespace hal
diff --git a/src/CRSFforArduino/src/SerialReceiver/CRC/CRC.cpp b/src/SerialReceiver/CRC/CRC.cpp
similarity index 94%
rename from src/CRSFforArduino/src/SerialReceiver/CRC/CRC.cpp
rename to src/SerialReceiver/CRC/CRC.cpp
index b54395d7..49e2a098 100644
--- a/src/CRSFforArduino/src/SerialReceiver/CRC/CRC.cpp
+++ b/src/SerialReceiver/CRC/CRC.cpp
@@ -1,11 +1,11 @@
/**
* @file CRC.cpp
* @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief CRC class implementation.
+ * @brief A generic CRC8 implementation for the CRSF for Arduino library.
* @version 1.0.0
- * @date 2024-1-20
+ * @date 2024-2-9
*
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
+ * @copyright Copyright (c) 2024, Cassandra "ZZ Cat" Robinson. All rights reserved.
*
* @section License GNU General Public License v3.0
* This source file is a part of the CRSF for Arduino library.
@@ -25,8 +25,9 @@
*/
#include "CRC.hpp"
+#include "stdlib.h"
-namespace serialReceiver
+namespace genericCrc
{
CRC::CRC()
{
@@ -133,5 +134,4 @@ namespace serialReceiver
#elif (CRC_OPTIMISATION_LEVEL == CRC_OPTIMISATION_HARDWARE)
#endif
}
-
-} // namespace serialReceiver
+} // namespace genericCrc
diff --git a/src/CRSFforArduino/src/SerialReceiver/CRC/CRC.hpp b/src/SerialReceiver/CRC/CRC.hpp
similarity index 87%
rename from src/CRSFforArduino/src/SerialReceiver/CRC/CRC.hpp
rename to src/SerialReceiver/CRC/CRC.hpp
index 66723d1f..cb609543 100644
--- a/src/CRSFforArduino/src/SerialReceiver/CRC/CRC.hpp
+++ b/src/SerialReceiver/CRC/CRC.hpp
@@ -1,11 +1,11 @@
/**
* @file CRC.hpp
* @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief CRC class declaration.
+ * @brief A generic CRC8 implementation for the CRSF for Arduino library.
* @version 1.0.0
- * @date 2024-1-20
+ * @date 2024-2-9
*
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
+ * @copyright Copyright (c) 2024, Cassandra "ZZ Cat" Robinson. All rights reserved.
*
* @section License GNU General Public License v3.0
* This header file is a part of the CRSF for Arduino library.
@@ -25,9 +25,10 @@
*/
#pragma once
-#include "Arduino.h"
-namespace serialReceiver
+#include "stdint.h"
+
+namespace genericCrc
{
#define CRC_OPTIMISATION_SPEED 0
#define CRC_OPTIMISATION_SIZE 1
@@ -49,4 +50,4 @@ namespace serialReceiver
uint8_t crc_8_dvb_s2(uint8_t crc, uint8_t data);
#endif
};
-} // namespace serialReceiver
+} // namespace genericCrc
diff --git a/src/CRSFforArduino/src/SerialReceiver/CRSF/CRSF.cpp b/src/SerialReceiver/CRSF/CRSF.cpp
similarity index 77%
rename from src/CRSFforArduino/src/SerialReceiver/CRSF/CRSF.cpp
rename to src/SerialReceiver/CRSF/CRSF.cpp
index bef9e910..b0365d8a 100644
--- a/src/CRSFforArduino/src/SerialReceiver/CRSF/CRSF.cpp
+++ b/src/SerialReceiver/CRSF/CRSF.cpp
@@ -1,11 +1,11 @@
/**
* @file CRSF.cpp
* @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief CRSF class implementation.
+ * @brief This decodes CRSF frames from a serial port.
* @version 1.0.0
- * @date 2024-1-20
+ * @date 2024-2-9
*
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
+ * @copyright Copyright (c) 2024, Cassandra "ZZ Cat" Robinson. All rights reserved.
*
* @section License GNU General Public License v3.0
* This source file is a part of the CRSF for Arduino library.
@@ -25,10 +25,12 @@
*/
#include "CRSF.hpp"
+#include "Arduino.h"
using namespace crsfProtocol;
+using namespace genericCrc;
-namespace serialReceiver
+namespace serialReceiverLayer
{
CRSF::CRSF()
{
@@ -130,6 +132,21 @@ namespace serialReceiver
rcFrameReceived = true;
}
break;
+
+#if CRSF_LINK_STATISTICS_ENABLED > 0
+ case CRSF_FRAMETYPE_LINK_STATISTICS:
+ if ((rxFrame.frame.deviceAddress == CRSF_ADDRESS_FLIGHT_CONTROLLER) && (rxFrame.frame.frameLength == CRSF_FRAME_ORIGIN_DEST_SIZE + CRSF_FRAME_LINK_STATISTICS_PAYLOAD_SIZE))
+ {
+ const crsf_payload_link_statistics_t *linkStatisticsPayload = (const crsf_payload_link_statistics_t *)&rxFrame.frame.payload;
+
+ /* Decode the link statistics. */
+ linkStatistics.rssi = (linkStatisticsPayload->active_antenna ? linkStatisticsPayload->uplink_rssi_2 : linkStatisticsPayload->uplink_rssi_1);
+ linkStatistics.lqi = linkStatisticsPayload->uplink_link_quality;
+ linkStatistics.snr = linkStatisticsPayload->uplink_snr;
+ linkStatistics.tx_power = (linkStatisticsPayload->uplink_tx_power < 9) ? tx_power_table[linkStatisticsPayload->uplink_tx_power] : 0;
+ }
+ break;
+#endif
}
}
// #ifdef USE_DMA
@@ -146,6 +163,18 @@ namespace serialReceiver
return false;
}
+ void CRSF::getFailSafe(bool *failSafe)
+ {
+ if (linkStatistics.lqi <= CRSF_FAILSAFE_LQI_THRESHOLD || linkStatistics.rssi >= CRSF_FAILSAFE_RSSI_THRESHOLD)
+ {
+ *failSafe = true;
+ }
+ else
+ {
+ *failSafe = false;
+ }
+ }
+
void CRSF::getRcChannels(uint16_t *rcChannels)
{
if (rcFrameReceived)
@@ -176,8 +205,17 @@ namespace serialReceiver
}
}
+ void CRSF::getLinkStatistics(link_statistics_t *linkStats)
+ {
+#if CRSF_LINK_STATISTICS_ENABLED > 0
+ /* Copy the link statistics into the output structure. */
+ memcpy(linkStats, &linkStatistics, sizeof(link_statistics_t));
+#else
+#endif
+ }
+
uint8_t CRSF::calculateFrameCRC()
{
return crc8->calculate(rxFrame.frame.type, rxFrame.frame.payload, rxFrame.frame.frameLength - CRSF_FRAME_LENGTH_TYPE_CRC);
}
-} // namespace serialReceiver
+} // namespace serialReceiverLayer
diff --git a/src/CRSFforArduino/src/SerialReceiver/CRSF/CRSF.hpp b/src/SerialReceiver/CRSF/CRSF.hpp
similarity index 64%
rename from src/CRSFforArduino/src/SerialReceiver/CRSF/CRSF.hpp
rename to src/SerialReceiver/CRSF/CRSF.hpp
index de6a17fb..a1e41376 100644
--- a/src/CRSFforArduino/src/SerialReceiver/CRSF/CRSF.hpp
+++ b/src/SerialReceiver/CRSF/CRSF.hpp
@@ -1,11 +1,11 @@
/**
* @file CRSF.hpp
* @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief CRSF class definition.
+ * @brief This decodes CRSF frames from a serial port.
* @version 1.0.0
- * @date 2024-1-20
+ * @date 2024-2-9
*
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
+ * @copyright Copyright (c) 2024, Cassandra "ZZ Cat" Robinson. All rights reserved.
*
* @section License GNU General Public License v3.0
* This header file is a part of the CRSF for Arduino library.
@@ -26,27 +26,34 @@
#pragma once
-#include "Arduino.h"
-#include "CRSFProtocol.hpp"
-#if defined(ARDUINO) && defined(PLATFORMIO)
-// #ifdef USE_DMA
-// #include "Hardware/DevBoards/DevBoards.hpp"
-// #endif
-#include "SerialReceiver/CRC/CRC.hpp"
-#elif defined(ARDUINO) && !defined(PLATFORMIO)
-// #ifdef USE_DMA
-// #include "lib/CRSFforArduino/src/Hardware/DevBoards/DevBoards.hpp"
-// #endif
#include "../CRC/CRC.hpp"
-#endif
-// #include "Hardware.h"
+#include "CRSFProtocol.hpp"
-namespace serialReceiver
+namespace serialReceiverLayer
{
- class CRSF
- // #ifdef USE_DMA
- // : private hal::DevBoards
+ // #if CRSF_LINK_STATISTICS_ENABLED > 0
+ typedef struct link_statistics_s
+ {
+ int16_t rssi = 0;
+ int16_t lqi = 0;
+ int16_t snr = 0;
+ int16_t tx_power = 0;
+ } link_statistics_t;
+
+ const uint16_t tx_power_table[9] = {
+ 0, // 0 mW
+ 10, // 10 mW
+ 25, // 25 mW
+ 100, // 100 mW
+ 500, // 500 mW
+ 1000, // 1 W
+ 2000, // 2 W
+ 250, // 250 mW
+ 50 // 50 mW
+ };
// #endif
+
+ class CRSF
{
public:
CRSF();
@@ -55,7 +62,9 @@ namespace serialReceiver
void end();
void setFrameTime(uint32_t baudRate, uint8_t packetCount = 10);
bool receiveFrames(uint8_t rxByte);
+ void getFailSafe(bool *failSafe);
void getRcChannels(uint16_t *rcChannels);
+ void getLinkStatistics(link_statistics_t *linkStats);
private:
bool rcFrameReceived;
@@ -63,7 +72,8 @@ namespace serialReceiver
uint32_t timePerFrame;
crsfProtocol::frame_t rxFrame;
crsfProtocol::frame_t rcChannelsFrame;
- CRC *crc8;
+ link_statistics_t linkStatistics;
+ genericCrc::CRC *crc8;
uint8_t calculateFrameCRC();
};
-} // namespace serialReceiver
+} // namespace serialReceiverLayer
diff --git a/src/CRSFforArduino/src/SerialReceiver/CRSF/CRSFProtocol.hpp b/src/SerialReceiver/CRSF/CRSFProtocol.hpp
similarity index 85%
rename from src/CRSFforArduino/src/SerialReceiver/CRSF/CRSFProtocol.hpp
rename to src/SerialReceiver/CRSF/CRSFProtocol.hpp
index e52f3b23..a6599447 100644
--- a/src/CRSFforArduino/src/SerialReceiver/CRSF/CRSFProtocol.hpp
+++ b/src/SerialReceiver/CRSF/CRSFProtocol.hpp
@@ -3,9 +3,9 @@
* @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
* @brief This file contains enums and structs for the CRSF protocol.
* @version 1.0.0
- * @date 2024-1-20
+ * @date 2024-2-9
*
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
+ * @copyright Copyright (c) 2024, Cassandra "ZZ Cat" Robinson. All rights reserved.
*
* @section License GNU General Public License v3.0
* This header file is a part of the CRSF for Arduino library.
@@ -24,9 +24,11 @@
*
*/
+#include "stdint.h"
+
#pragma once
-#include "Arduino.h"
+#include "../../CFA_Config.hpp"
namespace crsfProtocol
{
@@ -116,6 +118,10 @@ namespace crsfProtocol
CRSF_FRAMETYPE_DISPLAYPORT_CMD = 0x7D,
} frameType_t;
+#if CRSF_TELEMETRY_ENABLED == 1 || CRSF_LINK_STATISTICS_ENABLED == 1
+#define CRSF_FRAME_ORIGIN_DEST_SIZE 2
+#endif
+
typedef enum address_e
{
CRSF_ADDRESS_BROADCAST = 0x00,
@@ -184,6 +190,24 @@ namespace crsfProtocol
frameDefinition_t frame;
} frame_t;
+#if CRSF_LINK_STATISTICS_ENABLED > 0
+ // Link Statistics frame.
+ // Uplink is the connection from the transmitter to the receiver. Downlink is in the opposite direction.
+ typedef struct crsf_payload_link_statistics_s
+ {
+ uint8_t uplink_rssi_1; // Uplink RSSI Antenna 1 (dBm * -1)
+ uint8_t uplink_rssi_2; // Uplink RSSI Antenna 2 (dBm * -1)
+ uint8_t uplink_link_quality; // Uplink Link Quality/Packet Success Rate (%)
+ int8_t uplink_snr; // Uplink Signal-to-Noise Ratio (dB)
+ uint8_t active_antenna; // Active Antenna (0 = Antenna 1, 1 = Antenna 2)
+ uint8_t rf_mode; // RF Mode (4 fps = 0, 50 fps = 1, 150 fps = 2, 250 fps = 3, 500 fps = 4, 1000 fps = 5)
+ uint8_t uplink_tx_power; // Uplink TX Power (0 mW = 0, 10 mW = 1, 25 mW = 2, 100 mW = 3, 250 mW = 4, 500 mW = 5, 1000 mW = 6, 2000 mW = 7)
+ uint8_t downlink_rssi; // Downlink RSSI (dBm * -1)
+ uint8_t downlink_link_quality; // Downlink Link Quality/Packet Success Rate (%)
+ int8_t downlink_snr; // Downlink Signal-to-Noise Ratio (dB)
+ } crsf_payload_link_statistics_t;
+#endif
+
// Attitude Data to pass to the telemetry frame.
typedef struct attitudeData_s
{
diff --git a/src/CRSFforArduino/src/SerialReceiver/SerialBuffer/SerialBuffer.cpp b/src/SerialReceiver/SerialBuffer/SerialBuffer.cpp
similarity index 97%
rename from src/CRSFforArduino/src/SerialReceiver/SerialBuffer/SerialBuffer.cpp
rename to src/SerialReceiver/SerialBuffer/SerialBuffer.cpp
index 24371904..18fc6ce6 100644
--- a/src/CRSFforArduino/src/SerialReceiver/SerialBuffer/SerialBuffer.cpp
+++ b/src/SerialReceiver/SerialBuffer/SerialBuffer.cpp
@@ -1,11 +1,11 @@
/**
* @file SerialBuffer.cpp
* @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief SerialBuffer class implementation.
+ * @brief A generic serial buffer for the CRSF for Arduino library.
* @version 1.0.0
- * @date 2024-1-20
+ * @date 2024-2-9
*
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
+ * @copyright Copyright (c) 2024, Cassandra "ZZ Cat" Robinson. All rights reserved.
*
* @section License GNU General Public License v3.0
* This source file is a part of the CRSF for Arduino library.
@@ -25,6 +25,7 @@
*/
#include "SerialBuffer.hpp"
+#include "cstring"
namespace genericStreamBuffer
{
diff --git a/src/CRSFforArduino/src/SerialReceiver/SerialBuffer/SerialBuffer.hpp b/src/SerialReceiver/SerialBuffer/SerialBuffer.hpp
similarity index 82%
rename from src/CRSFforArduino/src/SerialReceiver/SerialBuffer/SerialBuffer.hpp
rename to src/SerialReceiver/SerialBuffer/SerialBuffer.hpp
index 0e38fb9e..2efcb5bc 100644
--- a/src/CRSFforArduino/src/SerialReceiver/SerialBuffer/SerialBuffer.hpp
+++ b/src/SerialReceiver/SerialBuffer/SerialBuffer.hpp
@@ -1,11 +1,11 @@
/**
* @file SerialBuffer.hpp
* @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief SerialBuffer class definition.
+ * @brief A generic serial buffer for the CRSF for Arduino library.
* @version 1.0.0
- * @date 2024-1-20
+ * @date 2024-2-9
*
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
+ * @copyright Copyright (c) 2024, Cassandra "ZZ Cat" Robinson. All rights reserved.
*
* @section License GNU General Public License v3.0
* This header file is a part of the CRSF for Arduino library.
@@ -26,25 +26,15 @@
#pragma once
-#include "Arduino.h"
-
-// #ifdef USE_DMA
-// #if defined(ARDUINO) && defined(PLATFORMIO)
-// #include "Hardware/DevBoards/DevBoards.hpp"
-// #elif defined(ARDUINO) && !defined(PLATFORMIO)
-// #include "lib/CRSFforArduino/src/Hardware/DevBoards/DevBoards.hpp"
-// #endif
-// #endif
+#include "stddef.h"
+#include "stdint.h"
namespace genericStreamBuffer
{
class SerialBuffer
- // #ifdef USE_DMA
- // : public hal::DevBoards
- // #endif
{
public:
- SerialBuffer(size_t size);
+ SerialBuffer(size_t size = 64);
~SerialBuffer();
void reset();
diff --git a/src/CRSFforArduino/src/SerialReceiver/SerialReceiver.cpp b/src/SerialReceiver/SerialReceiver.cpp
similarity index 68%
rename from src/CRSFforArduino/src/SerialReceiver/SerialReceiver.cpp
rename to src/SerialReceiver/SerialReceiver.cpp
index d74215ea..ec10f500 100644
--- a/src/CRSFforArduino/src/SerialReceiver/SerialReceiver.cpp
+++ b/src/SerialReceiver/SerialReceiver.cpp
@@ -1,14 +1,14 @@
/**
* @file SerialReceiver.cpp
* @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief This is the implementation file for the Serial Receiver Interface.
+ * @brief The Serial Receiver layer for the CRSF for Arduino library.
* @version 1.0.0
- * @date 2024-1-20
+ * @date 2024-2-9
*
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
+ * @copyright Copyright (c) 2024, Cassandra "ZZ Cat" Robinson. All rights reserved.
*
* @section License GNU General Public License v3.0
- * This header file is a part of the CRSF for Arduino library.
+ * This source file is a part of the CRSF for Arduino library.
* CRSF for Arduino is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
@@ -25,18 +25,23 @@
*/
#include "SerialReceiver.hpp"
+#include "../hal/CompatibilityTable/CompatibilityTable.hpp"
+#include "Arduino.h"
using namespace crsfProtocol;
+using namespace hal;
-namespace serialReceiver
+namespace serialReceiverLayer
{
SerialReceiver::SerialReceiver()
{
_uart = &Serial1;
- ct = new CompatibilityTable();
#if CRSF_RC_ENABLED > 0
- _rcChannels = new uint16_t[RC_CHANNEL_COUNT];
+ _rcChannels = new rcChannels_t;
+ _rcChannels->valid = false;
+ _rcChannels->failsafe = false;
+ memset(_rcChannels->value, 0, sizeof(_rcChannels->value));
#if CRSF_FLIGHTMODES_ENABLED > 0
_flightModes = new flightMode_t[FLIGHT_MODE_COUNT];
#endif
@@ -46,10 +51,12 @@ namespace serialReceiver
SerialReceiver::SerialReceiver(HardwareSerial *hwUartPort)
{
_uart = hwUartPort;
- ct = new CompatibilityTable();
#if CRSF_RC_ENABLED > 0
- _rcChannels = new uint16_t[RC_CHANNEL_COUNT];
+ _rcChannels = new rcChannels_t;
+ _rcChannels->valid = false;
+ _rcChannels->failsafe = false;
+ memset(_rcChannels->value, 0, sizeof(_rcChannels->value));
#if CRSF_FLIGHTMODES_ENABLED > 0
_flightModes = new flightMode_t[FLIGHT_MODE_COUNT];
#endif
@@ -59,10 +66,10 @@ namespace serialReceiver
SerialReceiver::~SerialReceiver()
{
_uart = nullptr;
- delete ct;
#if CRSF_RC_ENABLED > 0
- delete[] _rcChannels;
+ delete _rcChannels;
+ _rcChannels = nullptr;
#if CRSF_FLIGHTMODES_ENABLED > 0
delete[] _flightModes;
#endif
@@ -86,107 +93,107 @@ namespace serialReceiver
#if CRSF_RC_INITIALISE_ARMCHANNEL > 0 && CRSF_RC_INITIALISE_THROTTLECHANNEL > 0
if (i == RC_CHANNEL_AUX1 || i == RC_CHANNEL_THROTTLE)
{
- _rcChannels[i] = CRSF_RC_CHANNEL_MIN;
+ _rcChannels->value[i] = CRSF_RC_CHANNEL_MIN;
}
else
{
- _rcChannels[i] = CRSF_RC_CHANNEL_CENTER;
+ _rcChannels->value[i] = CRSF_RC_CHANNEL_CENTER;
}
#elif CRSF_RC_INITIALISE_ARMCHANNEL > 0
if (i == RC_CHANNEL_AUX1)
{
- _rcChannels[i] = CRSF_RC_CHANNEL_MIN;
+ _rcChannels->value[i] = CRSF_RC_CHANNEL_MIN;
}
else
{
- _rcChannels[i] = CRSF_RC_CHANNEL_CENTER;
+ _rcChannels->value[i] = CRSF_RC_CHANNEL_CENTER;
}
#elif CRSF_RC_INITIALISE_THROTTLECHANNEL > 0
if (i == RC_CHANNEL_THROTTLE)
{
- _rcChannels[i] = CRSF_RC_CHANNEL_MIN;
+ _rcChannels->value[i] = CRSF_RC_CHANNEL_MIN;
}
else
{
- _rcChannels[i] = CRSF_RC_CHANNEL_CENTER;
+ _rcChannels->value[i] = CRSF_RC_CHANNEL_CENTER;
}
#else
- _rcChannels[i] = CRSF_RC_CHANNEL_CENTER;
+ _rcChannels->value[i] = CRSF_RC_CHANNEL_CENTER;
#endif
}
#endif
- // Check if the _uart is compatible.
- if (ct->isDevboardCompatible(ct->getDevboardName()))
+ CompatibilityTable *ct = new CompatibilityTable();
+ if (!ct->isDevboardCompatible(ct->getDevboardName()))
{
- // _uart->enterCriticalSection();
-
- // Initialize the CRSF Protocol.
- crsf = new CRSF();
-
- // Check that the CRSF Protocol was initialized successfully.
- if (crsf == nullptr)
- {
- // _uart->exitCriticalSection();
+ delete ct;
+ ct = nullptr;
+ // _uart->exitCriticalSection();
#if CRSF_DEBUG_ENABLED > 0
- // Debug.
- CRSF_DEBUG_SERIAL_PORT.println("\n[Serial Receiver | FATAL ERROR]: CRSF Protocol could not be initialized.");
+ // Debug.
+ CRSF_DEBUG_SERIAL_PORT.println("\r\n[Serial Receiver | FATAL ERROR]: Devboard is not compatible with CRSF Protocol.");
#endif
- return false;
- }
+ return false;
+ }
- crsf->begin();
- crsf->setFrameTime(BAUD_RATE, 10);
- _uart->begin(BAUD_RATE);
+ delete ct;
+ ct = nullptr;
-#if CRSF_TELEMETRY_ENABLED > 0
- // Initialise telemetry.
- telemetry = new Telemetry();
+ // Initialize the CRSF Protocol.
+ crsf = new CRSF();
- // Check that the telemetry was initialised successfully.
- if (telemetry == nullptr)
- {
- // _uart->exitCriticalSection();
+ // Check that the CRSF Protocol was initialized successfully.
+ if (crsf == nullptr)
+ {
+ // _uart->exitCriticalSection();
#if CRSF_DEBUG_ENABLED > 0
- // Debug.
- CRSF_DEBUG_SERIAL_PORT.println("\n[Serial Receiver | FATAL ERROR]: Telemetry could not be initialized.");
+ // Debug.
+ CRSF_DEBUG_SERIAL_PORT.println("\n[Serial Receiver | FATAL ERROR]: CRSF Protocol could not be initialized.");
#endif
- return false;
- }
+ return false;
+ }
- telemetry->begin();
-#endif
+ crsf->begin();
+ crsf->setFrameTime(BAUD_RATE, 10);
+ _uart->begin(BAUD_RATE);
- // _uart->exitCriticalSection();
+#if CRSF_TELEMETRY_ENABLED > 0
+ // Initialise telemetry.
+ telemetry = new Telemetry();
- // Clear the UART buffer.
- _uart->flush();
- while (_uart->available() > 0)
- {
- _uart->read();
- }
+ // Check that the telemetry was initialised successfully.
+ if (telemetry == nullptr)
+ {
+ // _uart->exitCriticalSection();
#if CRSF_DEBUG_ENABLED > 0
// Debug.
- CRSF_DEBUG_SERIAL_PORT.println("Done.");
+ CRSF_DEBUG_SERIAL_PORT.println("\n[Serial Receiver | FATAL ERROR]: Telemetry could not be initialized.");
#endif
- return true;
+ return false;
}
- else
- {
- // _uart->exitCriticalSection();
- // This is now handled by the Compatibility Table.
- // #if CRSF_DEBUG_ENABLED > 0
- // Debug.
- // CRSF_DEBUG_SERIAL_PORT.println("\n[Serial Receiver | ERROR]: Devboard is not compatible.");
- // #endif
- return false;
+ telemetry->begin();
+#endif
+
+ // _uart->exitCriticalSection();
+
+ // Clear the UART buffer.
+ _uart->flush();
+ while (_uart->available() > 0)
+ {
+ _uart->read();
}
+
+#if CRSF_DEBUG_ENABLED > 0
+ // Debug.
+ CRSF_DEBUG_SERIAL_PORT.println("Done.");
+#endif
+ return true;
}
void SerialReceiver::end()
@@ -219,7 +226,7 @@ namespace serialReceiver
// _uart->exitCriticalSection();
}
-#if CRSF_RC_ENABLED > 0 || CRSF_TELEMETRY_ENABLED > 0
+#if CRSF_RC_ENABLED > 0 || CRSF_TELEMETRY_ENABLED > 0 || CRSF_LINK_STATISTICS_ENABLED > 0
void SerialReceiver::processFrames()
{
while (_uart->available() > 0)
@@ -228,6 +235,15 @@ namespace serialReceiver
{
flushRemainingFrames();
+#if CRSF_LINK_STATISTICS_ENABLED > 0
+ // Handle link statistics.
+ crsf->getLinkStatistics(&_linkStatistics);
+ if (_linkStatisticsCallback != nullptr)
+ {
+ _linkStatisticsCallback(_linkStatistics);
+ }
+#endif
+
#if CRSF_TELEMETRY_ENABLED > 0
// Check if it is time to send telemetry.
if (telemetry->update())
@@ -240,12 +256,24 @@ namespace serialReceiver
#if CRSF_RC_ENABLED > 0
// Update the RC Channels.
- crsf->getRcChannels(_rcChannels);
+ crsf->getFailSafe(&_rcChannels->failsafe);
+ crsf->getRcChannels(_rcChannels->value);
+ if (_rcChannelsCallback != nullptr)
+ {
+ _rcChannelsCallback(_rcChannels);
+ }
#endif
}
#endif
-#if CRSF_RC_ENABLED > 0 || CRSF_TELEMETRY_ENABLED > 0
+#if CRSF_LINK_STATISTICS_ENABLED > 0
+ void SerialReceiver::setLinkStatisticsCallback(linkStatisticsCallback_t callback)
+ {
+ _linkStatisticsCallback = callback;
+ }
+#endif
+
+#if CRSF_RC_ENABLED > 0 || CRSF_TELEMETRY_ENABLED > 0 || CRSF_LINK_STATISTICS_ENABLED > 0
void SerialReceiver::flushRemainingFrames()
{
_uart->flush();
@@ -257,13 +285,18 @@ namespace serialReceiver
#endif
#if CRSF_RC_ENABLED > 0
+ void SerialReceiver::setRcChannelsCallback(rcChannelsCallback_t callback)
+ {
+ _rcChannelsCallback = callback;
+ }
+
uint16_t SerialReceiver::readRcChannel(uint8_t channel, bool raw)
{
if (channel <= 15)
{
if (raw == true)
{
- return _rcChannels[channel];
+ return _rcChannels->value[channel];
}
else
{
@@ -274,7 +307,7 @@ namespace serialReceiver
- Scale factor = (2012 - 988) / (1811 - 172) = 0.62477120195241
- Offset = 988 - 172 * 0.62477120195241 = 880.53935326418548
*/
- return (uint16_t)((_rcChannels[channel] * 0.62477120195241F) + 881);
+ return (uint16_t)((_rcChannels->value[channel] * 0.62477120195241F) + 881);
}
}
else
@@ -398,4 +431,4 @@ namespace serialReceiver
}
#endif
#endif
-} // namespace serialReceiver
+} // namespace serialReceiverLayer
diff --git a/src/CRSFforArduino/src/SerialReceiver/SerialReceiver.hpp b/src/SerialReceiver/SerialReceiver.hpp
similarity index 72%
rename from src/CRSFforArduino/src/SerialReceiver/SerialReceiver.hpp
rename to src/SerialReceiver/SerialReceiver.hpp
index d808dca1..08d6d048 100644
--- a/src/CRSFforArduino/src/SerialReceiver/SerialReceiver.hpp
+++ b/src/SerialReceiver/SerialReceiver.hpp
@@ -1,14 +1,14 @@
/**
* @file SerialReceiver.hpp
* @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief This is the header file for the Serial Receiver Interface.
+ * @brief The Serial Receiver layer for the CRSF for Arduino library.
* @version 1.0.0
- * @date 2024-1-20
+ * @date 2024-2-9
*
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
+ * @copyright Copyright (c) 2024, Cassandra "ZZ Cat" Robinson. All rights reserved.
*
* @section License GNU General Public License v3.0
- * This header file is a part of the CRSF for Arduino library.
+ * This source file is a part of the CRSF for Arduino library.
* CRSF for Arduino is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
@@ -26,16 +26,12 @@
#pragma once
+#include "../CFA_Config.hpp"
#include "Arduino.h"
#include "CRSF/CRSF.hpp"
#include "Telemetry/Telemetry.hpp"
-#if defined(ARDUINO) && defined(PLATFORMIO)
-#include "Hardware/Hardware.hpp"
-#elif defined(ARDUINO) && !defined(PLATFORMIO)
-#include "../Hardware/Hardware.hpp"
-#endif
-namespace serialReceiver
+namespace serialReceiverLayer
{
typedef enum flightModeId_e
{
@@ -51,10 +47,23 @@ namespace serialReceiver
FLIGHT_MODE_COUNT
} flightModeId_t;
+ typedef struct rcChannels_s
+ {
+ bool valid;
+ bool failsafe;
+ uint16_t value[crsfProtocol::RC_CHANNEL_COUNT];
+ } rcChannels_t;
+
+ // Function pointer for RC Channels Callback
+ typedef void (*rcChannelsCallback_t)(rcChannels_t *);
+
// Function pointer for Flight Mode Callback
typedef void (*flightModeCallback_t)(flightModeId_t);
- class SerialReceiver : /* private CRSF, */ private CompatibilityTable /* , private hw_uart */
+ // Function pointer for Link Statistics Callback
+ typedef void (*linkStatisticsCallback_t)(link_statistics_t);
+
+ class SerialReceiver
{
public:
SerialReceiver();
@@ -64,11 +73,16 @@ namespace serialReceiver
bool begin();
void end();
-#if CRSF_RC_ENABLED > 0 || CRSF_TELEMETRY_ENABLED > 0
+#if CRSF_RC_ENABLED > 0 || CRSF_TELEMETRY_ENABLED > 0 || CRSF_LINK_STATISTICS_ENABLED > 0
void processFrames();
#endif
+#if CRSF_LINK_STATISTICS_ENABLED > 0
+ void setLinkStatisticsCallback(linkStatisticsCallback_t callback);
+#endif
+
#if CRSF_RC_ENABLED > 0
+ void setRcChannelsCallback(rcChannelsCallback_t callback);
uint16_t getChannel(uint8_t channel);
uint16_t rcToUs(uint16_t rc);
uint16_t usToRc(uint16_t us);
@@ -91,22 +105,26 @@ namespace serialReceiver
private:
CRSF *crsf;
- CompatibilityTable *ct;
HardwareSerial *_uart;
- // hw_uart *_uart;
#if CRSF_TELEMETRY_ENABLED > 0
Telemetry *telemetry;
#endif
#if CRSF_RC_ENABLED > 0
- uint16_t *_rcChannels;
+ rcChannels_t *_rcChannels = nullptr;
+ rcChannelsCallback_t _rcChannelsCallback = nullptr;
#endif
#if CRSF_TELEMETRY_ENABLED > 0
const char *flightModeStr = "ACRO";
#endif
+#if CRSF_LINK_STATISTICS_ENABLED > 0
+ link_statistics_t _linkStatistics;
+ linkStatisticsCallback_t _linkStatisticsCallback = nullptr;
+#endif
+
#if CRSF_RC_ENABLED > 0 && CRSF_FLIGHTMODES_ENABLED > 0
typedef struct flightMode_s
{
@@ -123,4 +141,4 @@ namespace serialReceiver
void flushRemainingFrames();
#endif
};
-} // namespace serialReceiver
+} // namespace serialReceiverLayer
diff --git a/src/CRSFforArduino/src/SerialReceiver/Telemetry/Telemetry.cpp b/src/SerialReceiver/Telemetry/Telemetry.cpp
similarity index 96%
rename from src/CRSFforArduino/src/SerialReceiver/Telemetry/Telemetry.cpp
rename to src/SerialReceiver/Telemetry/Telemetry.cpp
index 839fe65e..02500be9 100644
--- a/src/CRSFforArduino/src/SerialReceiver/Telemetry/Telemetry.cpp
+++ b/src/SerialReceiver/Telemetry/Telemetry.cpp
@@ -1,11 +1,11 @@
/**
* @file Telemetry.cpp
* @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief Telemetry class implementation.
+ * @brief This encodes data into CRSF telemetry frames for transmission to the RC handset.
* @version 1.0.0
- * @date 2024-1-20
+ * @date 2024-2-9
*
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
+ * @copyright Copyright (c) 2024, Cassandra "ZZ Cat" Robinson. All rights reserved.
*
* @section License GNU General Public License v3.0
* This source file is a part of the CRSF for Arduino library.
@@ -25,18 +25,19 @@
*/
#include "Telemetry.hpp"
-#if defined(ARDUINO) && defined(PLATFORMIO)
#include "CFA_Config.hpp"
-#elif defined(ARDUINO) && !defined(PLATFORMIO)
-#include "../../CFA_Config.hpp"
-#endif
using namespace crsfProtocol;
-namespace serialReceiver
+namespace serialReceiverLayer
{
-#define PI 3.1415926535897932384626433832795F
+#ifndef PI
+#define PI 3.1415926535897932384626433832795F
+#endif
+
+#ifndef RAD
#define RAD PI / 180.0F
+#endif
Telemetry::Telemetry() :
CRC(), SerialBuffer(CRSF_FRAME_SIZE_MAX)
@@ -319,4 +320,4 @@ namespace serialReceiver
SerialBuffer::writeU8(crc);
}
-} // namespace serialReceiver
+} // namespace serialReceiverLayer
diff --git a/src/CRSFforArduino/src/SerialReceiver/Telemetry/Telemetry.hpp b/src/SerialReceiver/Telemetry/Telemetry.hpp
similarity index 77%
rename from src/CRSFforArduino/src/SerialReceiver/Telemetry/Telemetry.hpp
rename to src/SerialReceiver/Telemetry/Telemetry.hpp
index 78f67819..8eb55757 100644
--- a/src/CRSFforArduino/src/SerialReceiver/Telemetry/Telemetry.hpp
+++ b/src/SerialReceiver/Telemetry/Telemetry.hpp
@@ -1,11 +1,11 @@
/**
* @file Telemetry.hpp
* @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief Telemetry class definition.
+ * @brief This encodes data into CRSF telemetry frames for transmission to the RC handset.
* @version 1.0.0
- * @date 2024-1-20
+ * @date 2024-2-9
*
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
+ * @copyright Copyright (c) 2024, Cassandra "ZZ Cat" Robinson. All rights reserved.
*
* @section License GNU General Public License v3.0
* This header file is a part of the CRSF for Arduino library.
@@ -28,25 +28,13 @@
#include "Arduino.h"
-#if defined(ARDUINO) && defined(PLATFORMIO)
-// #include "Hardware/hw_uart/hw_uart.hpp"
-#include "SerialReceiver/CRC/CRC.hpp"
-#include "SerialReceiver/CRSF/CRSFProtocol.hpp"
-#include "SerialReceiver/SerialBuffer/SerialBuffer.hpp"
-#elif defined(ARDUINO) && !defined(PLATFORMIO)
-// #include "../../Hardware/hw_uart/hw_uart.hpp"
#include "../CRC/CRC.hpp"
#include "../CRSF/CRSFProtocol.hpp"
#include "../SerialBuffer/SerialBuffer.hpp"
-#endif
-namespace serialReceiver
+namespace serialReceiverLayer
{
- class Telemetry : private CRC, private genericStreamBuffer::SerialBuffer
- // #ifndef USE_DMA
- /*`,
- private hal::hw_uart */
- // #endif
+ class Telemetry : private genericCrc::CRC, private genericStreamBuffer::SerialBuffer
{
public:
Telemetry();
@@ -83,4 +71,4 @@ namespace serialReceiver
// void _appendVarioData();
void _finaliseFrame();
};
-} // namespace serialReceiver
+} // namespace serialReceiverLayer
diff --git a/src/CRSFforArduino/src/Hardware/CompatibilityTable/CompatibilityTable.cpp b/src/hal/CompatibilityTable/CompatibilityTable.cpp
similarity index 95%
rename from src/CRSFforArduino/src/Hardware/CompatibilityTable/CompatibilityTable.cpp
rename to src/hal/CompatibilityTable/CompatibilityTable.cpp
index 0efb87ce..ee93ca93 100644
--- a/src/CRSFforArduino/src/Hardware/CompatibilityTable/CompatibilityTable.cpp
+++ b/src/hal/CompatibilityTable/CompatibilityTable.cpp
@@ -1,12 +1,11 @@
/**
* @file CompatibilityTable.cpp
* @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief This is the implementation of the Compatibility Table.
- * It is used to determine if the target development board is compatible with CRSF for Arduino.
+ * @brief The Compatibility Table determines if the target development board is compatible with CRSF for Arduino.
* @version 1.0.0
- * @date 2024-1-20
+ * @date 2024-2-9
*
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
+ * @copyright Copyright (c) 2024, Cassandra "ZZ Cat" Robinson. All rights reserved.
*
* @section License GNU General Public License v3.0
* This source file is a part of the CRSF for Arduino library.
@@ -26,11 +25,8 @@
*/
#include "CompatibilityTable.hpp"
-#if defined(ARDUINO) && defined(PLATFORMIO)
-#include "./CFA_Config.hpp"
-#elif defined(ARDUINO) && !defined(PLATFORMIO)
-#include "./CRSFforArduino/src/CFA_Config.hpp"
-#endif
+#include "../../CFA_Config.hpp"
+#include "Arduino.h"
namespace hal
{
@@ -99,6 +95,22 @@ namespace hal
device.type.devboard = DEVBOARD_IS_PERMISSIVELY_INCOMPATIBLE_UNKNOWN_BOARD;
#endif
+// Raspberry Pi RP2040 Architecture
+#elif defined(ARDUINO_ARCH_RP2040)
+
+// Arduino Nano RP2040 Connect
+#if defined(ARDUINO_NANO_RP2040_CONNECT)
+ device.type.devboard = DEVBOARD_ARDUINO_NANO_RP2040_CONNECT;
+
+// Raspberry Pi Pico
+#elif defined(ARDUINO_RASPBERRY_PI_PICO)
+ device.type.devboard = DEVBOARD_RASPBERRYPI_PICO;
+#else
+ // The architecture and chip is known, but the board is not.
+#warning "The target board is unknown. Please enable CRSF_DEBUG_ENABLED and CRSF_DEBUG_ENABLE_COMPATIBILITY_TABLE_OUTPUT in CFA_Config.hpp for more information."
+ device.type.devboard = DEVBOARD_IS_PERMISSIVELY_INCOMPATIBLE_UNKNOWN_BOARD;
+#endif
+
// Arduino SAMD Architecture
#elif defined(ARDUINO_ARCH_SAMD)
diff --git a/src/CRSFforArduino/src/Hardware/CompatibilityTable/CompatibilityTable.hpp b/src/hal/CompatibilityTable/CompatibilityTable.hpp
similarity index 93%
rename from src/CRSFforArduino/src/Hardware/CompatibilityTable/CompatibilityTable.hpp
rename to src/hal/CompatibilityTable/CompatibilityTable.hpp
index 371d8da2..735f2fbe 100644
--- a/src/CRSFforArduino/src/Hardware/CompatibilityTable/CompatibilityTable.hpp
+++ b/src/hal/CompatibilityTable/CompatibilityTable.hpp
@@ -1,11 +1,11 @@
/**
* @file CompatibilityTable.hpp
* @author Cassandra "ZZ Cat" Robinson (nicad.heli.flier@gmail.com)
- * @brief This is the Compatibility Table header file.
+ * @brief The Compatibility Table determines if the target development board is compatible with CRSF for Arduino.
* @version 1.0.0
- * @date 2024-1-20
+ * @date 2024-2-9
*
- * @copyright Copyright (c) 2023, Cassandra "ZZ Cat" Robinson. All rights reserved.
+ * @copyright Copyright (c) 2024, Cassandra "ZZ Cat" Robinson. All rights reserved.
*
* @section License GNU General Public License v3.0
* This header file is a part of the CRSF for Arduino library.
@@ -26,8 +26,6 @@
#pragma once
-#include "Arduino.h"
-
namespace hal
{
class CompatibilityTable
@@ -84,6 +82,9 @@ namespace hal
// Arduino ESP32 boards.
DEVBOARD_ARDUINO_NANO_ESP32,
+ // Arduino RP2040 boards.
+ DEVBOARD_ARDUINO_NANO_RP2040_CONNECT,
+
// Arduino SAMD21 boards.
DEVBOARD_ARDUINO_MKR1000,
DEVBOARD_ARDUINO_MKRFOX1200,
@@ -101,6 +102,9 @@ namespace hal
DEVBOARD_ESPRESSIF_ESP32C3_DEVKIT,
DEVBOARD_ESPRESSIF_ESP32S3_DEVKIT,
+ // Raspberry Pi RP2040 boards.
+ DEVBOARD_RASPBERRYPI_PICO,
+
// Seeed Studio boards.
DEVBOARD_SEEEDSTUDIO_XIAO_ESP32C3,
DEVBOARD_SEEEDSTUDIO_XIAO_ESP32S3,
@@ -162,6 +166,7 @@ namespace hal
"Adafruit Metro M4 Express",
"Adafruit Feather M4 CAN",
"Arduino Nano ESP32",
+ "Arduino Nano RP2040 Connect",
"Arduino MKR1000",
"Arduino MKRFOX1200",
"Arduino MKRGSM1400",
@@ -175,6 +180,7 @@ namespace hal
"Arduino Zero",
"Espressif ESP32-C3 DevKit",
"Espressif ESP32-S3 DevKit",
+ "Raspberry Pi Pico",
"Seeed Studio Xiao ESP32-C3",
"Seeed Studio Xiao ESP32-S3",
"Seeed Studio Xiao SAMD21",
diff --git a/targets/adafruit_unified_esp32.ini b/targets/adafruit_unified_esp32.ini
deleted file mode 100644
index 781aed41..00000000
--- a/targets/adafruit_unified_esp32.ini
+++ /dev/null
@@ -1,39 +0,0 @@
-[env:adafruit_qtpy_esp32]
-extends = env_common_esp32
-board = adafruit_qtpy_esp32
-
-[env:adafruit_qtpy_esp32c3]
-extends = env_common_esp32
-board = adafruit_qtpy_esp32c3
-
-[env:adafruit_qtpy_esp32s2]
-extends = env_common_esp32
-board = adafruit_qtpy_esp32s2
-
-[env:adafruit_qtpy_esp32s3_nopsram]
-extends = env_common_esp32
-board = adafruit_qtpy_esp32s3_nopsram
-
-[env:adafruit_feather_esp32s3]
-extends = env_common_esp32
-board = adafruit_feather_esp32s3
-
-[env:adafruit_feather_esp32s3_nopsram]
-extends = env_common_esp32
-board = adafruit_feather_esp32s3_nopsram
-
-[env:adafruit_itsybitsy_esp32]
-extends = env_common_esp32
-board = adafruit_itsybitsy_esp32
-
-[env:adafruit_metro_esp32s2]
-extends = env_common_esp32
-board = adafruit_metro_esp32s2
-
-[env:featheresp32]
-extends = env_common_esp32
-board = featheresp32
-
-[env:featheresp32-s2]
-extends = env_common_esp32
-board = featheresp32-s2
diff --git a/targets/adafruit_unified_samd21.ini b/targets/adafruit_unified_samd21.ini
deleted file mode 100644
index b97ce074..00000000
--- a/targets/adafruit_unified_samd21.ini
+++ /dev/null
@@ -1,15 +0,0 @@
-[env:adafruit_feather_m0]
-extends = env_common_samd21
-board = adafruit_feather_m0
-
-[env:adafruit_feather_m0_express]
-extends = env_common_samd21
-board = adafruit_feather_m0_express
-
-[env:adafruit_itsybitsy_m0]
-extends = env_common_samd21
-board = adafruit_itsybitsy_m0
-
-[env:adafruit_metro_m0]
-extends = env_common_samd21
-board = adafruit_metro_m0
diff --git a/targets/arduino_unified_esp32.ini b/targets/arduino_unified_esp32.ini
deleted file mode 100644
index 410efbf1..00000000
--- a/targets/arduino_unified_esp32.ini
+++ /dev/null
@@ -1,3 +0,0 @@
-[env:arduino_nano_esp32]
-extends = env_common_esp32
-board = arduino_nano_esp32
diff --git a/targets/common.ini b/targets/common.ini
index 72ad6463..1d1917d9 100644
--- a/targets/common.ini
+++ b/targets/common.ini
@@ -8,14 +8,16 @@ fastest = -Ofast
here_be_dragons = -Ofast -funroll-loops
[common]
-build_flags =
- -DUSE_ABSTRACTION_LAYER
+build_flags =
-DCRC_OPTIMISATION_LEVEL=0
${optimise_level.fastest}
[env_common_esp32]
platform = espressif32@6.4.0
+[env_common_rp2040]
+platform = raspberrypi@1.11.0
+
[env_common_samd21]
platform = atmelsam@8.2.0
@@ -28,9 +30,9 @@ platform = teensy@4.18.0
[env]
framework = arduino
build_src_filter =
- -
- +
- -
+ +<../examples/platformio/main.cpp>
+ +<*/*/*.cpp>
+ +<*.cpp>
build_unflags =
-Os
build_flags =
diff --git a/targets/espressif_unified_esp32.ini b/targets/espressif_unified_esp32.ini
deleted file mode 100644
index d33f4d4f..00000000
--- a/targets/espressif_unified_esp32.ini
+++ /dev/null
@@ -1,11 +0,0 @@
-[env:esp32-c3-devkit-02]
-extends = env_common_esp32
-board = esp32-c3-devkitc-02
-
-[env:esp32-c3-devkitm-1]
-extends = env_common_esp32
-board = esp32-c3-devkitm-1
-
-[env:esp32-s3-devkitc-1]
-extends = env_common_esp32
-board = esp32-s3-devkitc-1
diff --git a/targets/seeed_studio_esp32.ini b/targets/seeed_studio_esp32.ini
deleted file mode 100644
index 32cfd1e6..00000000
--- a/targets/seeed_studio_esp32.ini
+++ /dev/null
@@ -1,7 +0,0 @@
-[env:seeed_xiao_esp32c3]
-extends = env_common_esp32
-board = seeed_xiao_esp32c3
-
-[env:seeed_xiao_esp32s3]
-extends = env_common_esp32
-board = seeed_xiao_esp32s3
diff --git a/targets/seeed_studio_samd21.ini b/targets/seeed_studio_samd21.ini
deleted file mode 100644
index 3105ce66..00000000
--- a/targets/seeed_studio_samd21.ini
+++ /dev/null
@@ -1,3 +0,0 @@
-[env:seeed_xiao]
-extends = env_common_samd21
-board = seeed_xiao
diff --git a/targets/sparkfun_unified_esp32.ini b/targets/sparkfun_unified_esp32.ini
deleted file mode 100644
index a5d7c467..00000000
--- a/targets/sparkfun_unified_esp32.ini
+++ /dev/null
@@ -1,15 +0,0 @@
-[env:esp32thing]
-extends = env_common_esp32
-board = esp32thing
-
-[env:esp32thing_plus]
-extends = env_common_esp32
-board = esp32thing_plus
-
-[env:sparkfun_esp32_iot_redboard]
-extends = env_common_esp32
-board = sparkfun_esp32_iot_redboard
-
-[env:sparkfun_esp32s2_thing_plus]
-extends = env_common_esp32
-board = sparkfun_esp32s2_thing_plus
diff --git a/targets/unified_esp32.ini b/targets/unified_esp32.ini
new file mode 100644
index 00000000..0bc1b742
--- /dev/null
+++ b/targets/unified_esp32.ini
@@ -0,0 +1,79 @@
+[env:adafruit_qtpy_esp32]
+extends = env_common_esp32
+board = adafruit_qtpy_esp32
+
+[env:adafruit_qtpy_esp32c3]
+extends = env_common_esp32
+board = adafruit_qtpy_esp32c3
+
+[env:adafruit_qtpy_esp32s2]
+extends = env_common_esp32
+board = adafruit_qtpy_esp32s2
+
+[env:adafruit_qtpy_esp32s3_nopsram]
+extends = env_common_esp32
+board = adafruit_qtpy_esp32s3_nopsram
+
+[env:adafruit_feather_esp32s3]
+extends = env_common_esp32
+board = adafruit_feather_esp32s3
+
+[env:adafruit_feather_esp32s3_nopsram]
+extends = env_common_esp32
+board = adafruit_feather_esp32s3_nopsram
+
+[env:adafruit_itsybitsy_esp32]
+extends = env_common_esp32
+board = adafruit_itsybitsy_esp32
+
+[env:adafruit_metro_esp32s2]
+extends = env_common_esp32
+board = adafruit_metro_esp32s2
+
+[env:adafruit_feather_esp32]
+extends = env_common_esp32
+board = featheresp32
+
+[env:adafruit_feather_esp32-s2]
+extends = env_common_esp32
+board = featheresp32-s2
+
+[env:arduino_nano_esp32]
+extends = env_common_esp32
+board = arduino_nano_esp32
+
+[env:esp32-c3-devkit-02]
+extends = env_common_esp32
+board = esp32-c3-devkitc-02
+
+[env:esp32-c3-devkitm-1]
+extends = env_common_esp32
+board = esp32-c3-devkitm-1
+
+[env:esp32-s3-devkitc-1]
+extends = env_common_esp32
+board = esp32-s3-devkitc-1
+
+[env:seeed_xiao_esp32c3]
+extends = env_common_esp32
+board = seeed_xiao_esp32c3
+
+[env:seeed_xiao_esp32s3]
+extends = env_common_esp32
+board = seeed_xiao_esp32s3
+
+[env:sparkfun_esp32_thing]
+extends = env_common_esp32
+board = esp32thing
+
+[env:sparkfun_esp32_thing_plus]
+extends = env_common_esp32
+board = esp32thing_plus
+
+[env:sparkfun_esp32_iot_redboard]
+extends = env_common_esp32
+board = sparkfun_esp32_iot_redboard
+
+[env:sparkfun_esp32s2_thing_plus]
+extends = env_common_esp32
+board = sparkfun_esp32s2_thing_plus
diff --git a/targets/unified_rp2040.ini b/targets/unified_rp2040.ini
new file mode 100644
index 00000000..a173d9a8
--- /dev/null
+++ b/targets/unified_rp2040.ini
@@ -0,0 +1,7 @@
+[env:arduino_nano_rp2040_connect]
+extends = env_common_rp2040
+board = nanorp2040connect
+
+[env:raspberrypi_pico_rp2040]
+extends = env_common_rp2040
+board = pico
diff --git a/targets/arduino_unified_samd21.ini b/targets/unified_samd21.ini
similarity index 50%
rename from targets/arduino_unified_samd21.ini
rename to targets/unified_samd21.ini
index d28be6c7..65b6cf02 100644
--- a/targets/arduino_unified_samd21.ini
+++ b/targets/unified_samd21.ini
@@ -1,43 +1,43 @@
-[env:mkrfox1200]
+[env:adafruit_feather_m0]
extends = env_common_samd21
-board = mkrfox1200
+board = adafruit_feather_m0
-[env:mkrgsm1400]
+[env:adafruit_feather_m0_express]
extends = env_common_samd21
-board = mkrgsm1400
+board = adafruit_feather_m0_express
-[env:mkrnb1500]
+[env:adafruit_itsybitsy_m0]
extends = env_common_samd21
-board = mkrnb1500
+board = adafruit_itsybitsy_m0
-[env:mkrvidor4000]
+[env:adafruit_metro_m0]
extends = env_common_samd21
-board = mkrvidor4000
+board = adafruit_metro_m0
-[env:mkrwan1300]
-extends = env_common_samd21
-board = mkrwan1300
-
-[env:mkrwan1310]
+[env:arduino_mkrwan1310]
extends = env_common_samd21
board = mkrwan1310
-[env:mkrwifi1010]
+[env:arduino_mkrwifi1010]
extends = env_common_samd21
board = mkrwifi1010
-[env:mkrzero]
+[env:arduino_mkrzero]
extends = env_common_samd21
board = mkrzero
-[env:nano_33_iot]
+[env:arduino_nano_33_iot]
extends = env_common_samd21
board = nano_33_iot
-[env:zero]
+[env:arduino_zero]
extends = env_common_samd21
board = zero
-[env:zeroUSB]
+[env:arduino_zeroUSB]
extends = env_common_samd21
board = zeroUSB
+
+[env:seeed_xiao_samd21]
+extends = env_common_samd21
+board = seeed_xiao
diff --git a/targets/adafruit_unified_samd51.ini b/targets/unified_samd51.ini
similarity index 100%
rename from targets/adafruit_unified_samd51.ini
rename to targets/unified_samd51.ini
diff --git a/targets/teensy_unified.ini b/targets/unified_teensy3x.ini
similarity index 71%
rename from targets/teensy_unified.ini
rename to targets/unified_teensy3x.ini
index 74cb5ab6..b81f8911 100644
--- a/targets/teensy_unified.ini
+++ b/targets/unified_teensy3x.ini
@@ -17,11 +17,3 @@ board = teensy35
[env:teensy_36]
extends = env_common_teensy
board = teensy36
-
-[env:teensy_40]
-extends = env_common_teensy
-board = teensy40
-
-[env:teensy_41]
-extends = env_common_teensy
-board = teensy41
diff --git a/targets/unified_teensy4x.ini b/targets/unified_teensy4x.ini
new file mode 100644
index 00000000..9b0bcdb9
--- /dev/null
+++ b/targets/unified_teensy4x.ini
@@ -0,0 +1,7 @@
+[env:teensy_40]
+extends = env_common_teensy
+board = teensy40
+
+[env:teensy_41]
+extends = env_common_teensy
+board = teensy41