Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add MAVLink support to Backpack #141

Merged
merged 24 commits into from
Aug 3, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
24 commits
Select commit Hold shift + click to select a range
2fc9771
Add MAVLink to Backpack
MUSTARDTIGERFPV Jul 18, 2024
c27a5af
Require multiple heartbeats to go to MAVLink mode
MUSTARDTIGERFPV Jul 18, 2024
9a0ba91
Better way to pull UID
MUSTARDTIGERFPV Jul 18, 2024
12f7077
Fix build, add more HTTP info
MUSTARDTIGERFPV Jul 19, 2024
a5638d6
Actually fix build (he says)
MUSTARDTIGERFPV Jul 19, 2024
f5b0982
Fix Debug builds
MUSTARDTIGERFPV Jul 19, 2024
c6d1f1f
Maybe actually fix build
MUSTARDTIGERFPV Jul 19, 2024
fc28ec2
Move ifdefs to the right section
MUSTARDTIGERFPV Jul 19, 2024
dbfff20
Move closing paren (surely this will build)
MUSTARDTIGERFPV Jul 19, 2024
c39a340
Make name consistent
MUSTARDTIGERFPV Jul 19, 2024
70325fd
Refactor WiFi MAVLink packet handling and counters
MUSTARDTIGERFPV Jul 24, 2024
ccd5c55
Fixes packet drops & adds some counters - still a few changes to make
MUSTARDTIGERFPV Jul 25, 2024
c0c727b
Clean up stats, add bidirectional framing
MUSTARDTIGERFPV Jul 25, 2024
d243c74
Remove uplink framing, clean up stats
MUSTARDTIGERFPV Jul 25, 2024
2478f43
Merge remote-tracking branch 'origin' into backpack-mavlink
MUSTARDTIGERFPV Jul 28, 2024
ed9456f
Fix overflow behavior
MUSTARDTIGERFPV Jul 29, 2024
215fc7e
Let Backpack be taken out of WiFi mode by a MAVLink message
MUSTARDTIGERFPV Jul 29, 2024
996da62
Actually, let's use a COMMAND_INT type
MUSTARDTIGERFPV Jul 29, 2024
5297dee
Fix syntax
MUSTARDTIGERFPV Jul 29, 2024
b309fe5
Update magic number name
MUSTARDTIGERFPV Jul 29, 2024
3468cf5
Move shouldForward
MUSTARDTIGERFPV Jul 29, 2024
16b6eb8
Fix no-MAVLink build
MUSTARDTIGERFPV Jul 30, 2024
7aafb0c
Enable MAVLink support for ESP32-C3 TX backpacks
MUSTARDTIGERFPV Jul 30, 2024
721cfd2
Backpack now follows TX immediately when set to MAVLink mode
MUSTARDTIGERFPV Jul 30, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 3 additions & 2 deletions lib/BUTTON/devButton.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#include <Arduino.h>
#include "common.h"
#include "device.h"
#include "config.h"

#if defined(PIN_BUTTON)
#include "logging.h"
Expand All @@ -9,7 +10,7 @@
static Button<PIN_BUTTON, false> button;

extern unsigned long rebootTime;
void RebootIntoWifi();
void RebootIntoWifi(wifi_service_t service);

static void shortPress()
{
Expand All @@ -19,7 +20,7 @@ static void shortPress()
}
else
{
RebootIntoWifi();
RebootIntoWifi(WIFI_SERVICE_UPDATE);
}
}

Expand Down
51 changes: 51 additions & 0 deletions lib/MAVLink/MAVLink.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
#if defined(MAVLINK_ENABLED)
#include <Arduino.h>
#include "MAVLink.h"
#include <config.h>

// Returns whether the message is a control message, i.e. a message where we don't want to
// pass the message to the flight controller, but rather handle it ourselves. If the message
// is a control message, the function handles it internally.
bool MAVLink::handleControlMessage(mavlink_message_t *msg)
{
bool shouldForward = true;
// Check for messages addressed to the Backpack
switch (msg->msgid)
{
case MAVLINK_MSG_ID_COMMAND_INT:
mavlink_command_int_t commandMsg;
mavlink_msg_command_int_decode(msg, &commandMsg);
if (commandMsg.target_component == MAV_COMP_ID_UDP_BRIDGE)
{
shouldForward = false;
constexpr uint8_t ELRS_MODE_CHANGE = 0x8;
switch (commandMsg.command)
{
case MAV_CMD_USER_1:
switch ((int)commandMsg.param1)
{
case ELRS_MODE_CHANGE:
switch ((int)commandMsg.param2)
{
case 0: // TX_NORMAL_MODE
config.SetStartWiFiOnBoot(false);
ESP.restart();
break;
case 1: // TX_MAVLINK_MODE
if (config.GetWiFiService() != WIFI_SERVICE_MAVLINK_TX)
{
config.SetWiFiService(WIFI_SERVICE_MAVLINK_TX);
config.SetStartWiFiOnBoot(true);
config.Commit();
ESP.restart();
}
break;
}
}
}
break;
}
}
return shouldForward;
}
#endif
9 changes: 9 additions & 0 deletions lib/MAVLink/MAVLink.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
#if defined(MAVLINK_ENABLED)
#include "common/mavlink.h"

class MAVLink
{
public:
static bool handleControlMessage(mavlink_message_t* msg);
};
#endif
175 changes: 172 additions & 3 deletions lib/WIFI/devWIFI.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,11 +33,16 @@
#include "WebContent.h"

#include "config.h"

#if defined(MAVLINK_ENABLED)
#include <MAVLink.h>
#endif
#if defined(TARGET_VRX_BACKPACK)
extern VrxBackpackConfig config;
extern bool sendRTCChangesToVrx;
#elif defined(TARGET_TX_BACKPACK)
extern TxBackpackConfig config;
extern wifi_service_t wifiService;
#elif defined(TARGET_TIMER_BACKPACK)
extern TimerBackpackConfig config;
#else
Expand All @@ -50,7 +55,8 @@ static const char *myHostname = "elrs_vrx";
static const char *wifi_ap_ssid = "ExpressLRS VRx Backpack";
#elif defined(TARGET_TX_BACKPACK)
static const char *myHostname = "elrs_txbp";
static const char *wifi_ap_ssid = "ExpressLRS TX Backpack";
static char wifi_ap_ssid[33]; // will be set depending on wifiService

#elif defined(TARGET_TIMER_BACKPACK)
static const char *myHostname = "elrs_timer";
static const char *wifi_ap_ssid = "ExpressLRS Timer Backpack";
Expand All @@ -74,6 +80,7 @@ static volatile unsigned long changeTime = 0;
static const byte DNS_PORT = 53;
static IPAddress apIP(10, 0, 0, 1);
static IPAddress netMsk(255, 255, 255, 0);
static IPAddress apBroadcast(10, 0, 0, 255);
static DNSServer dnsServer;

static AsyncWebServer server(80);
Expand All @@ -92,6 +99,34 @@ static AsyncEventSource logging("/logging");
static char logBuffer[256];
static int logPos = 0;

#if defined(MAVLINK_ENABLED)
// This is the port that we will listen for mavlink packets on
constexpr uint16_t MAVLINK_PORT_LISTEN = 14555;
// This is the port that we will send mavlink packets to
constexpr uint16_t MAVLINK_PORT_SEND = 14550;
// Size of the buffer that we will use to store mavlink packets in units of mavlink_message_t
constexpr size_t MAVLINK_BUF_SIZE = 16;
// Threshold at which we will flush the buffer
constexpr size_t MAVLINK_BUF_THRESHOLD = MAVLINK_BUF_SIZE / 2;
// Timeout for flushing the buffer in ms
constexpr size_t MAVLINK_BUF_TIMEOUT = 500;

WiFiUDP mavlinkUDP;

typedef struct {
uint32_t packets_downlink; // packets from the aircraft
uint32_t packets_uplink; // packets to the aircraft
uint32_t drops_downlink; // dropped packets from the aircraft
//uint32_t drops_uplink; // framing in the uplink direction cost too much time
uint32_t overflows_downlink; // buffer overflows from the aircraft
} mavlink_stats_t;
mavlink_stats_t mavlink_stats;
// Buffer for storing mavlink packets from the aircraft so that we can send them to the GCS efficiently
mavlink_message_t mavlink_to_gcs_buf[MAVLINK_BUF_SIZE];
// Count of the number of messages in the buffer
uint8_t mavlink_to_gcs_buf_count = 0;
#endif

/** Is this an IP? */
static boolean isIp(String str)
{
Expand Down Expand Up @@ -447,6 +482,24 @@ static void WebUploadRTCUpdateHandler(AsyncWebServerRequest *request) {
#endif
}

#if defined(MAVLINK_ENABLED)
static void WebMAVLinkHandler(AsyncWebServerRequest *request)
MUSTARDTIGERFPV marked this conversation as resolved.
Show resolved Hide resolved
{
DynamicJsonDocument json(1024);
json["enabled"] = wifiService == WIFI_SERVICE_MAVLINK_TX;
json["counters"]["packets_down"] = mavlink_stats.packets_downlink;
json["counters"]["packets_up"] = mavlink_stats.packets_uplink;
json["counters"]["drops_down"] = mavlink_stats.drops_downlink;
json["counters"]["overflows_down"] = mavlink_stats.overflows_downlink;
json["ports"]["listen"] = MAVLINK_PORT_LISTEN;
json["ports"]["send"] = MAVLINK_PORT_SEND;

AsyncResponseStream *response = request->beginResponseStream("application/json");
serializeJson(json, *response);
request->send(response);
}
#endif

static void wifiOff()
{
wifiStarted = false;
Expand Down Expand Up @@ -586,6 +639,9 @@ static void startServices()
#if defined(AAT_BACKPACK)
WebAatInit(server);
#endif
#if defined(MAVLINK_ENABLED)
server.on("/mavlink", HTTP_GET, WebMAVLinkHandler);
MUSTARDTIGERFPV marked this conversation as resolved.
Show resolved Hide resolved
#endif

server.on("/log.js", WebUpdateSendContent);
server.on("/log.html", WebUpdateSendContent);
Expand All @@ -599,6 +655,9 @@ static void startServices()
dnsServer.setErrorReplyCode(DNSReplyCode::NoError);

startMDNS();
#if defined(MAVLINK_ENABLED)
mavlinkUDP.begin(MAVLINK_PORT_LISTEN);
MUSTARDTIGERFPV marked this conversation as resolved.
Show resolved Hide resolved
#endif

servicesStarted = true;
DBGLN("HTTPUpdateServer ready! Open http://%s.local in your browser", myHostname);
Expand Down Expand Up @@ -643,6 +702,18 @@ static void HandleWebUpdate()
#endif
changeTime = now;
WiFi.softAPConfig(apIP, apIP, netMsk);
#if defined(TARGET_TX_BACKPACK)
if (wifiService == WIFI_SERVICE_UPDATE) {
strcpy(wifi_ap_ssid, "ExpressLRS TX Backpack");
} else if (wifiService == WIFI_SERVICE_MAVLINK_TX) {
// Generate a unique SSID using config.address as hex
sprintf(wifi_ap_ssid, "ExpressLRS TX Backpack %02X%02X%02X",
firmwareOptions.uid[3],
firmwareOptions.uid[4],
firmwareOptions.uid[5]
);
}
#endif
WiFi.softAP(wifi_ap_ssid, wifi_ap_password);
WiFi.scanNetworks(true);
startServices();
Expand All @@ -666,23 +737,121 @@ static void HandleWebUpdate()

if (servicesStarted)
{
while (Serial.available()) {
while (Serial.available())
{
#if defined(MAVLINK_ENABLED)
if (wifiService == WIFI_SERVICE_UPDATE)
{
int val = Serial.read();
logBuffer[logPos++] = val;
logBuffer[logPos] = 0;
if (val == '\n' || logPos == sizeof(logBuffer) - 1)
{
logging.send(logBuffer);
logPos = 0;
}
}
else if (wifiService == WIFI_SERVICE_MAVLINK_TX)
{
mavlink_status_t status;
char val = Serial.read();
static uint8_t expectedSeq = 0;
static bool expectedSeqSet = false;
if (mavlink_to_gcs_buf_count >= MAVLINK_BUF_SIZE)
{
mavlink_stats.overflows_downlink++;
mavlink_to_gcs_buf_count = 0;
}
mavlink_message_t msg;
if (mavlink_frame_char(MAVLINK_COMM_0, val, &msg, &status) != MAVLINK_FRAMING_INCOMPLETE)
{
bool shouldForward = MAVLink::handleControlMessage(&msg);
if (shouldForward)
{
// Track gaps in the sequence number, add to a dropped counter
uint8_t seq = msg.seq;
if (expectedSeqSet && seq != expectedSeq)
{
// account for rollovers
if (seq < expectedSeq)
{
mavlink_stats.drops_downlink += (UINT8_MAX - expectedSeq) + seq;
}
else
{
mavlink_stats.drops_downlink += seq - expectedSeq;
}
}
expectedSeq = seq + 1;
expectedSeqSet = true;
// Forward the message to the GCS
mavlink_to_gcs_buf[mavlink_to_gcs_buf_count] = msg;
mavlink_to_gcs_buf_count++;
mavlink_stats.packets_downlink++;
}
}
}
#else
int val = Serial.read();
logBuffer[logPos++] = val;
logBuffer[logPos] = 0;
if (val == '\n' || logPos == sizeof(logBuffer)-1) {
if (val == '\n' || logPos == sizeof(logBuffer) - 1)
{
logging.send(logBuffer);
logPos = 0;
}
#endif
}

#if defined(MAVLINK_ENABLED)
// Dump the mavlink_to_gcs_buf to the GCS
static unsigned long last_mavlink_to_gcs_dump = 0;
if (
mavlink_to_gcs_buf_count > MAVLINK_BUF_THRESHOLD || // buffer is full enough
(mavlink_to_gcs_buf_count > 0 && (millis() - last_mavlink_to_gcs_dump) > MAVLINK_BUF_TIMEOUT) // buffer hasn't been flushed in a while
)
{
IPAddress broadcast = WiFi.getMode() == WIFI_STA ? WiFi.broadcastIP() : apBroadcast;
mavlinkUDP.beginPacket(broadcast, MAVLINK_PORT_SEND);
for (uint8_t i = 0; i < mavlink_to_gcs_buf_count; i++)
{
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
uint16_t len = mavlink_msg_to_send_buffer(buf, &mavlink_to_gcs_buf[i]);
size_t sent = mavlinkUDP.write(buf, len);
if (sent < len)
{
break;
}
}
mavlinkUDP.endPacket();
mavlink_to_gcs_buf_count = 0;
last_mavlink_to_gcs_dump = millis();
}
#endif

#if defined(MAVLINK_ENABLED)
// Check if we have MAVLink UDP data to send over UART
if (wifiService == WIFI_SERVICE_MAVLINK_TX) {
int packetSize = mavlinkUDP.parsePacket();
if (packetSize) {
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
mavlinkUDP.read(buf, packetSize);
Serial.write(buf, packetSize);
mavlink_stats.packets_uplink++; // this isn't necessarily a single mavlink packet, but framing was too time expensive.
}
}
#endif
dnsServer.processNextRequest();
#if defined(PLATFORM_ESP8266)
MDNS.update();
#endif
// When in STA mode, a small delay reduces power use from 90mA to 30mA when idle
// In AP mode, it doesn't seem to make a measurable difference, but does not hurt
#if defined(MAVLINK_ENABLED)
if (!updater.isRunning() && wifiService != WIFI_SERVICE_MAVLINK_TX)
#else
if (!updater.isRunning())
#endif
delay(1);
if (do_flash) {
do_flash = false;
Expand Down
7 changes: 7 additions & 0 deletions lib/config/config.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@ TxBackpackConfig::SetDefaults()
m_config.ssid[0] = 0;
m_config.password[0] = 0;
memset(m_config.address, 0, 6);
m_config.wifiService = WIFI_SERVICE_UPDATE;
m_modified = true;
Commit();
}
Expand Down Expand Up @@ -83,6 +84,12 @@ TxBackpackConfig::SetGroupAddress(const uint8_t address[6])
m_modified = true;
}

void
TxBackpackConfig::SetWiFiService(wifi_service_t service)
{
m_config.wifiService = service;
m_modified = true;
}
#endif

/////////////////////////////////////////////////////
Expand Down
Loading