Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
52 changes: 52 additions & 0 deletions lib/WIFI/devWIFI.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,6 +119,58 @@ IPAddress gcsIP;
bool gcsIPSet = false;
#endif

#if defined(TARGET_TX_BACKPACK)
bool SendTxBackpackTelemetryViaUDP(const uint8_t *data, uint16_t size)
{
if (!data || size == 0)
{
return false;
}

#if !defined(MAVLINK_ENABLED)
return false;
#else
if (!servicesStarted || !wifiStarted)
{
return false;
}
if (wifiService != WIFI_SERVICE_MAVLINK_TX)
{
return false;
}

IPAddress remote;
WiFiMode_t mode = WiFi.getMode();
if (mode == WIFI_AP || mode == WIFI_AP_STA)
{
remote = apBroadcast;
}
else if (mode == WIFI_STA)
{
remote = WiFi.broadcastIP();
}
else
{
return false;
}

if (!mavlinkUDP.beginPacket(remote, config.GetMavlinkSendPort()))
{
return false;
}

size_t sent = mavlinkUDP.write(data, size);
if (sent != size)
{
mavlinkUDP.endPacket();
return false;
}

return mavlinkUDP.endPacket() == 1;
#endif
}
#endif

/** Is this an IP? */
static boolean isIp(String str)
{
Expand Down
6 changes: 5 additions & 1 deletion lib/WIFI/devWIFI.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,4 +7,8 @@ extern device_t WIFI_device;
#define HAS_WIFI

extern const char *VERSION;
#endif

#if defined(TARGET_TX_BACKPACK)
bool SendTxBackpackTelemetryViaUDP(const uint8_t *data, uint16_t size);
#endif
#endif
19 changes: 19 additions & 0 deletions src/Tx_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,7 @@ MAVLink mavlink;
/////////// FUNCTION DEFS ///////////

void sendMSPViaEspnow(mspPacket_t *packet);
void sendMSPViaWiFiUDP(mspPacket_t *packet);

/////////////////////////////////////

Expand Down Expand Up @@ -224,6 +225,10 @@ void ProcessMSPPacketFromTX(mspPacket_t *packet)

case MSP_ELRS_BACKPACK_CRSF_TLM:
DBGLN("Processing MSP_ELRS_BACKPACK_CRSF_TLM...");
if (config.GetTelemMode() == BACKPACK_TELEM_MODE_WIFI)
{
sendMSPViaWiFiUDP(packet);
}
if (config.GetTelemMode() != BACKPACK_TELEM_MODE_OFF)
{
sendMSPViaEspnow(packet);
Expand Down Expand Up @@ -288,6 +293,20 @@ void sendMSPViaEspnow(mspPacket_t *packet)
blinkLED();
}

void sendMSPViaWiFiUDP(mspPacket_t *packet)
{
uint8_t packetSize = msp.getTotalPacketSize(packet);
uint8_t dataOutput[packetSize];

uint8_t result = msp.convertToByteArray(packet, dataOutput);
if (!result)
{
return;
}

SendTxBackpackTelemetryViaUDP(dataOutput, packetSize);
}

void SendCachedMSP()
{
if (!cacheFull)
Expand Down