Skip to content

Commit 77447c3

Browse files
authored
MFD Crossbow tracker integration (#150)
* Add support for MFD Crossbow trackers as an ESPNOW receiver that converts CRSF to MAVLink
1 parent 9048f68 commit 77447c3

File tree

9 files changed

+397
-12
lines changed

9 files changed

+397
-12
lines changed

hardware/targets.json

Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -548,5 +548,34 @@
548548
"platform": "esp8285"
549549
}
550550
}
551+
},
552+
"mfd-crossbow": {
553+
"name": "MFD Crossbow Antenna Tracker Backpack",
554+
"aat": {
555+
"esp82": {
556+
"product_name": "Generic ESP8285 / ESP8266 Receiver",
557+
"firmware": "MFD_Crossbow_ESP8285_Backpack",
558+
"upload_methods": ["uart", "wifi"],
559+
"platform": "esp8285"
560+
},
561+
"esp32": {
562+
"product_name": "Generic ESP32 Receiver",
563+
"firmware": "MFD_Crossbow_ESP32_Backpack",
564+
"upload_methods": ["uart", "wifi"],
565+
"platform": "esp32"
566+
},
567+
"esp32c3": {
568+
"product_name": "Generic ESP32C3 Receiver",
569+
"firmware": "MFD_Crossbow_ESP32C3_Backpack",
570+
"upload_methods": ["uart", "wifi"],
571+
"platform": "esp32-c3"
572+
},
573+
"esp32s3": {
574+
"product_name": "Generic ESP32S3 Receiver",
575+
"firmware": "MFD_Crossbow_ESP32S3_Backpack",
576+
"upload_methods": ["uart", "wifi"],
577+
"platform": "esp32-s3"
578+
}
579+
}
551580
}
552581
}

lib/LED/devLED.cpp

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,13 @@ static uint8_t _pin_inverted = true;
1616
#else
1717
static uint8_t _pin_inverted = false;
1818
#endif
19+
20+
#define UNDEF_PIN (-1)
21+
22+
#ifndef PIN_LED
23+
#define PIN_LED UNDEF_PIN
24+
#endif
25+
1926
static uint8_t _pin = -1;
2027
static const uint8_t *_durations;
2128
static uint8_t _count;
@@ -65,7 +72,7 @@ static int event()
6572
if (connectionState == running && blipLED)
6673
{
6774
digitalWrite(PIN_LED, LOW ^ _pin_inverted);
68-
return 200; // 200ms off
75+
return 50; // 50ms off
6976
}
7077
if (connectionState == binding)
7178
{

platformio.ini

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,3 +16,4 @@ extra_configs =
1616
targets/rapidfire.ini
1717
targets/rx5808.ini
1818
targets/skyzone.ini
19+
targets/mfd_crossbow.ini

src/Vrx_main.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,8 @@
4040
#include "orqa.h"
4141
#elif defined(AAT_BACKPACK)
4242
#include "module_aat.h"
43+
#elif defined(CROSSBOW_BACKPACK)
44+
#include "mfd_crossbow.h"
4345
#endif
4446

4547
/////////// DEFINES ///////////
@@ -116,6 +118,8 @@ VrxBackpackConfig config;
116118
Orqa vrxModule;
117119
#elif defined(AAT_BACKPACK)
118120
AatModule vrxModule(Serial);
121+
#elif defined(CROSSBOW_BACKPACK)
122+
MFDCrossbow vrxModule(&Serial);
119123
#endif
120124

121125
/////////// FUNCTION DEFS ///////////
@@ -328,6 +332,7 @@ void SetSoftMACAddress()
328332

329333
void RequestVTXPacket()
330334
{
335+
#if !defined(AAT_BACKPACK) and !defined(CROSSBOW_BACKPACK)
331336
mspPacket_t packet;
332337
packet.reset();
333338
packet.makeCommand();
@@ -336,6 +341,7 @@ void RequestVTXPacket()
336341

337342
blinkLED();
338343
sendMSPViaEspnow(&packet);
344+
#endif
339345
}
340346

341347
void sendMSPViaEspnow(mspPacket_t *packet)

src/mfd_crossbow.cpp

Lines changed: 124 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,124 @@
1+
#include "mfd_crossbow.h"
2+
#include "common/mavlink.h"
3+
4+
MFDCrossbow::MFDCrossbow(HardwareSerial *port) :
5+
m_port(port),
6+
gpsLastSent(0),
7+
gpsLastUpdated(0),
8+
heading(0),
9+
lat(0.0),
10+
lon(0.0),
11+
alt(0.0),
12+
groundspeed(0.0),
13+
gps_sats(0),
14+
gps_alt(0),
15+
gps_hdop(100),
16+
fixType(3)
17+
{
18+
}
19+
20+
void
21+
MFDCrossbow::SendHeartbeat()
22+
{
23+
// Initialize the required buffers
24+
mavlink_message_t msg;
25+
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
26+
27+
// Pack the message
28+
mavlink_msg_heartbeat_pack(MAVLINK_SYSTEM_ID, MAVLINK_COMPONENT_ID, &msg, MAVLINK_SYSTEM_TYPE, MAVLINK_AUTOPILOT_TYPE, MAVLINK_SYSTEM_MODE, MAVLINK_CUSTOM_MODE, MAVLINK_SYSTEM_STATE);
29+
30+
// Copy the message to the send buffer
31+
uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);
32+
33+
// Send the message
34+
m_port->write(buf, len);
35+
}
36+
37+
void
38+
MFDCrossbow::SendGpsRawInt()
39+
{
40+
// Initialize the required buffers
41+
mavlink_message_t msg;
42+
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
43+
44+
const uint16_t eph = UINT16_MAX;
45+
const uint16_t epv = UINT16_MAX;
46+
const uint16_t cog = UINT16_MAX;
47+
const uint32_t alt_ellipsoid = 0;
48+
const uint32_t h_acc = 0;
49+
const uint32_t v_acc = 0;
50+
const uint32_t vel_acc = 0;
51+
const uint32_t hdg_acc = 0;
52+
53+
// Pack the message
54+
mavlink_msg_gps_raw_int_pack(MAVLINK_SYSTEM_ID, MAVLINK_COMPONENT_ID, &msg, MAVLINK_UPTIME, fixType, lat, lon, alt, eph, epv, groundspeed, cog, gps_sats, alt_ellipsoid, h_acc, v_acc, vel_acc, hdg_acc, heading);
55+
56+
// Copy the message to the send buffer
57+
uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);
58+
59+
// Send the message
60+
m_port->write(buf, len);
61+
}
62+
63+
void
64+
MFDCrossbow::SendGlobalPositionInt()
65+
{
66+
const int16_t velx = 0;
67+
const int16_t vely = 0;
68+
const int16_t velz = 0;
69+
70+
// Initialize the required buffers
71+
mavlink_message_t msg;
72+
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
73+
74+
// Pack the message
75+
mavlink_msg_global_position_int_pack(MAVLINK_SYSTEM_ID, MAVLINK_COMPONENT_ID, &msg, MAVLINK_UPTIME, lat, lon, gps_alt, alt, velx, vely, velz, heading);
76+
77+
// Copy the message to the send buffer
78+
uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);
79+
80+
// Send the message
81+
m_port->write(buf, len);
82+
}
83+
84+
void
85+
MFDCrossbow::SendGpsTelemetry(crsf_packet_gps_t *packet)
86+
{
87+
int32_t rawLat = be32toh(packet->p.lat); // Convert to host byte order
88+
int32_t rawLon = be32toh(packet->p.lon); // Convert to host byte order
89+
lat = static_cast<double>(rawLat);
90+
lon = static_cast<double>(rawLon);
91+
92+
// Convert from CRSF scales to mavlink scales
93+
groundspeed = be16toh(packet->p.speed) / 36.0 * 100.0;
94+
heading = be16toh(packet->p.heading);
95+
alt = (be16toh(packet->p.altitude) - 1000) * 1000.0;
96+
gps_alt = alt;
97+
gps_sats = packet->p.satcnt;
98+
99+
// Send heartbeat and GPS mavlink messages to the tracker
100+
SendHeartbeat();
101+
SendGpsRawInt();
102+
SendGlobalPositionInt();
103+
104+
// Log the last time we received new GPS coords
105+
gpsLastUpdated = millis();
106+
}
107+
108+
void
109+
MFDCrossbow::Loop(uint32_t now)
110+
{
111+
ModuleBase::Loop(now);
112+
113+
// If the GPS data is <= 10 seconds old, keep spamming it out at 10hz
114+
bool gpsIsValid = (now < gpsLastUpdated + 10000) && gps_sats > 0;
115+
116+
if (now > gpsLastSent + 100 && gpsIsValid)
117+
{
118+
SendHeartbeat();
119+
SendGpsRawInt();
120+
SendGlobalPositionInt();
121+
122+
gpsLastSent = now;
123+
}
124+
}

src/mfd_crossbow.h

Lines changed: 42 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,42 @@
1+
#pragma once
2+
3+
#include "module_base.h"
4+
#include "msptypes.h"
5+
6+
#define VRX_UART_BAUD 115200
7+
8+
#define MAVLINK_SYSTEM_ID 1
9+
#define MAVLINK_COMPONENT_ID 1
10+
#define MAVLINK_SYSTEM_TYPE 1
11+
#define MAVLINK_AUTOPILOT_TYPE 3
12+
#define MAVLINK_SYSTEM_MODE 64
13+
#define MAVLINK_CUSTOM_MODE 0
14+
#define MAVLINK_SYSTEM_STATE 4
15+
#define MAVLINK_UPTIME 0
16+
17+
class MFDCrossbow : public ModuleBase
18+
{
19+
public:
20+
MFDCrossbow(HardwareSerial *port);
21+
void SendGpsTelemetry(crsf_packet_gps_t *packet);
22+
void Loop(uint32_t now);
23+
24+
private:
25+
void SendHeartbeat();
26+
void SendGpsRawInt();
27+
void SendGlobalPositionInt();
28+
29+
HardwareSerial *m_port;
30+
uint32_t gpsLastSent;
31+
uint32_t gpsLastUpdated;
32+
33+
int16_t heading; // Geographical heading angle in degrees
34+
float lat; // GPS latitude in degrees (example: 47.123456)
35+
float lon; // GPS longitude in degrees
36+
float alt; // Relative flight altitude in m
37+
float groundspeed; // Groundspeed in m/s
38+
int16_t gps_sats; // Number of visible GPS satellites
39+
int32_t gps_alt; // GPS altitude (Altitude above MSL)
40+
float gps_hdop; // GPS HDOP
41+
uint8_t fixType; // GPS fix type. 0-1: no fix, 2: 2D fix, 3: 3D fix
42+
};

targets/aat.ini

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@ lib_ignore = STM32UPDATE
2222
lib_deps =
2323
${env.lib_deps}
2424
adafruit/Adafruit SSD1306 @ 2.5.9
25-
build_src_filter = ${common_env_data.build_src_filter} -<Tx_main.cpp> -<rapidfire.*> -<rx5808.*> -<steadyview.*> -<Timer_main.cpp>
25+
build_src_filter = ${common_env_data.build_src_filter} -<Tx_main.cpp> -<rapidfire.*> -<rx5808.*> -<steadyview.*> -<Timer_main.cpp> -<mfd_crossbow.*>
2626

2727
[env:AAT_ESP_Backpack_via_WIFI]
2828
extends = env:AAT_ESP_Backpack_via_UART

0 commit comments

Comments
 (0)