Skip to content

Commit 234a388

Browse files
author
Devin Barillari
committed
Add Raw Crsf BackPack Target
# Conflicts: # targets/common.ini
1 parent b5b7675 commit 234a388

9 files changed

Lines changed: 169 additions & 1 deletion

File tree

hardware/targets.json

Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -610,5 +610,34 @@
610610
"platform": "esp32-s3"
611611
}
612612
}
613+
},
614+
"raw-crsf": {
615+
"name": "Raw CRSF Backpack",
616+
"aat": {
617+
"esp82": {
618+
"product_name": "Generic ESP8285 / ESP8266 Receiver",
619+
"firmware": "Raw_CRSF_ESP8285_Backpack",
620+
"upload_methods": ["uart", "wifi"],
621+
"platform": "esp8285"
622+
},
623+
"esp32": {
624+
"product_name": "Generic ESP32 Receiver",
625+
"firmware": "Raw_CRSF_ESP32_Backpack",
626+
"upload_methods": ["uart", "wifi"],
627+
"platform": "esp32"
628+
},
629+
"esp32c3": {
630+
"product_name": "Generic ESP32C3 Receiver",
631+
"firmware": "Raw_CRSF_ESP32C3_Backpack",
632+
"upload_methods": ["uart", "wifi"],
633+
"platform": "esp32-c3"
634+
},
635+
"esp32s3": {
636+
"product_name": "Generic ESP32S3 Receiver",
637+
"firmware": "Raw_CRSF_ESP32S3_Backpack",
638+
"upload_methods": ["uart", "wifi"],
639+
"platform": "esp32-s3"
640+
}
641+
}
613642
}
614643
}

platformio.ini

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

src/Vrx_main.cpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,8 @@
4343
#include "module_aat.h"
4444
#elif defined(CROSSBOW_BACKPACK)
4545
#include "mfd_crossbow.h"
46+
#elif defined(RAW_CRSF_BACKPACK)
47+
#include "raw_crsf.h"
4648
#endif
4749

4850
/////////// DEFINES ///////////
@@ -124,6 +126,8 @@ VrxBackpackConfig config;
124126
AatModule vrxModule(Serial);
125127
#elif defined(CROSSBOW_BACKPACK)
126128
MFDCrossbow vrxModule(&Serial);
129+
#elif defined(RAW_CRSF_BACKPACK)
130+
CRSFBackPack vrxModule(&Serial);
127131
#endif
128132

129133
/////////// FUNCTION DEFS ///////////
@@ -260,6 +264,7 @@ void ProcessMSPPacket(mspPacket_t *packet)
260264
DBGLN("CRSF_TLM packet too short")
261265
break;
262266
}
267+
vrxModule.SendRawTelemetry(packet->payload, packet->payloadSize);
263268
switch (packet->payload[2]) {
264269
case CRSF_FRAMETYPE_GPS:
265270
vrxModule.SendGpsTelemetry((crsf_packet_gps_t *)packet->payload);

src/module_base.cpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -59,6 +59,11 @@ ModuleBase::SendBatteryTelemetry(uint8_t *rawCrsfPacket)
5959
{
6060
}
6161

62+
void
63+
ModuleBase::SendRawTelemetry(uint8_t *rawCrsfPacket, uint16_t size)
64+
{
65+
}
66+
6267
void
6368
ModuleBase::Loop(uint32_t now)
6469
{

src/module_base.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@ class ModuleBase
1616
void SendLinkTelemetry(uint8_t *rawCrsfPacket);
1717
void SendBatteryTelemetry(uint8_t *rawCrsfPacket);
1818
void SendGpsTelemetry(crsf_packet_gps_t *packet) {}
19+
void SendRawTelemetry(uint8_t *rawCrsfPacket, uint16_t size);
1920
void Loop(uint32_t now);
2021
};
2122

src/raw_crsf.cpp

Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,29 @@
1+
#include "raw_crsf.h"
2+
3+
CRSFBackPack::CRSFBackPack(HardwareSerial *port) :
4+
m_port(port),
5+
lastSent(0),
6+
lastUpdated(0)
7+
{
8+
}
9+
10+
void
11+
CRSFBackPack::SendRawTelemetry(uint8_t *rawCrsfPacket, uint16_t size)
12+
{
13+
lastUpdated = millis();
14+
m_port->write(rawCrsfPacket, size);
15+
}
16+
17+
void
18+
CRSFBackPack::Loop(uint32_t now)
19+
{
20+
ModuleBase::Loop(now);
21+
22+
// If the GPS data is <= 10 seconds old, keep spamming it out at 10hz
23+
bool gpsIsValid = (now < lastUpdated + 10000);
24+
25+
if (now > lastSent + 100 && gpsIsValid)
26+
{
27+
lastSent = now;
28+
}
29+
}

src/raw_crsf.h

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,23 @@
1+
#pragma once
2+
3+
#include "module_base.h"
4+
#include "msptypes.h"
5+
6+
#define VRX_UART_BAUD 115200
7+
8+
class CRSFBackPack : public ModuleBase
9+
{
10+
public:
11+
CRSFBackPack(HardwareSerial *port);
12+
void SendRawTelemetry(uint8_t *rawCrsfPacket, uint16_t size);
13+
void Loop(uint32_t now);
14+
15+
private:
16+
void SendHeartbeat();
17+
void SendGpsRawInt();
18+
void SendGlobalPositionInt();
19+
20+
HardwareSerial *m_port;
21+
uint32_t lastSent;
22+
uint32_t lastUpdated;
23+
};

targets/common.ini

Lines changed: 32 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -96,6 +96,7 @@ build_src_filter =
9696
-<orqa.*>
9797
-<Timer_main.cpp>
9898
-<mfd_crossbow.*>
99+
-<raw_crsf.*>
99100

100101
# ------------------------- COMMON RAPIDFIRE-BACKPACK DEFINITIONS -----------------
101102
[rapidfire_vrx_backpack_common]
@@ -116,6 +117,7 @@ build_src_filter =
116117
-<orqa.*>
117118
-<Timer_main.cpp>
118119
-<mfd_crossbow.*>
120+
-<raw_crsf.*>
119121

120122
# ------------------------- COMMON RX5808-BACKPACK DEFINITIONS -----------------
121123
[rx5808_vrx_backpack_common]
@@ -136,6 +138,7 @@ build_src_filter =
136138
-<orqa.*>
137139
-<Timer_main.cpp>
138140
-<mfd_crossbow.*>
141+
-<raw_crsf.*>
139142

140143
# ------------------------- COMMON STEADYVIEW-BACKPACK DEFINITIONS -----------------
141144
[steadyview_vrx_backpack_common]
@@ -156,6 +159,7 @@ build_src_filter =
156159
-<orqa.*>
157160
-<Timer_main.cpp>
158161
-<mfd_crossbow.*>
162+
-<raw_crsf.*>
159163

160164
# ------------------------- COMMON FUSION-BACKPACK DEFINITIONS -----------------
161165
[fusion_vrx_backpack_common]
@@ -176,6 +180,7 @@ build_src_filter =
176180
-<orqa.*>
177181
-<Timer_main.cpp>
178182
-<mfd_crossbow.*>
183+
-<raw_crsf.*>
179184

180185
# ------------------------- COMMON HDZERO-BACKPACK DEFINITIONS -----------------
181186
[hdzero_vrx_backpack_common]
@@ -196,6 +201,7 @@ build_src_filter =
196201
-<orqa.*>
197202
-<Timer_main.cpp>
198203
-<mfd_crossbow.*>
204+
-<raw_crsf.*>
199205

200206
# ------------------------- COMMON SKYZONE-MSP-BACKPACK DEFINITIONS -----------------
201207
[skyzone_msp_vrx_backpack_common]
@@ -216,6 +222,7 @@ build_src_filter =
216222
-<orqa.*>
217223
-<Timer_main.cpp>
218224
-<mfd_crossbow.*>
225+
-<raw_crsf.*>
219226

220227
# ------------------------- COMMON ORQA-BACKPACK DEFINITIONS -------------------
221228
[orqa_backpack_common]
@@ -236,6 +243,7 @@ build_src_filter =
236243
; -<orqa.*>
237244
-<Timer_main.cpp>
238245
-<mfd_crossbow.*>
246+
-<raw_crsf.*>
239247

240248
# ------------------------- COMMON TIMER-BACKPACK DEFINITIONS -----------------
241249
[timer_backpack_common]
@@ -255,6 +263,7 @@ build_src_filter =
255263
-<orqa.*>
256264
; -<Timer_main.cpp>
257265
-<mfd_crossbow.*>
266+
-<raw_crsf.*>
258267

259268
# ------------------------- COMMON MFD-CROSSBOW-BACKPACK DEFINITIONS -----------------
260269
[mfd_crossbow_backpack_common]
@@ -275,6 +284,28 @@ build_src_filter =
275284
-<orqa.*>
276285
-<Timer_main.cpp>
277286
; -<mfd_crossbow.*>
287+
-<raw_crsf.*>
278288
lib_deps =
279289
${env.lib_deps}
280-
${common_env_data.mavlink_lib_dep}
290+
${common_env_data.mavlink_lib_dep}
291+
292+
# ------------------------- COMMON RAW-CRSF-BACKPACK DEFINITIONS -----------------
293+
[raw_crsf_backpack_common]
294+
build_flags =
295+
${common_env_data.build_flags}
296+
-D TARGET_VRX_BACKPACK
297+
-D RAW_CRSF_BACKPACK
298+
build_src_filter =
299+
${common_env_data.build_src_filter}
300+
-<Tx_main.cpp>
301+
; -<Vrx_main.cpp>
302+
-<rapidfire.*>
303+
-<rx5808.*>
304+
-<steadyview.*>
305+
-<fusion.*>
306+
-<hdzero.*>
307+
-<skyzone_msp.*>
308+
-<orqa.*>
309+
-<Timer_main.cpp>
310+
-<mfd_crossbow.*>
311+
; -<raw_crsf.*>

targets/raw_crsf.ini

Lines changed: 44 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,44 @@
1+
# ********************************
2+
# MFD Crossbow tracker backpack
3+
# ********************************
4+
5+
[env:Raw_CRSF_ESP8285_Backpack_via_UART]
6+
extends = env_common_esp8285, raw_crsf_backpack_common
7+
build_flags =
8+
${env_common_esp8285.build_flags}
9+
${raw_crsf_backpack_common.build_flags}
10+
-D PIN_BUTTON=0
11+
-D PIN_LED=16
12+
13+
[env:Raw_CRSF_ESP8285_Backpack_via_WIFI]
14+
extends = env:Raw_CRSF_ESP8285_Backpack_via_UART
15+
16+
[env:Raw_CRSF_ESP32_Backpack_via_UART]
17+
extends = env_common_esp32, raw_crsf_backpack_common
18+
build_flags =
19+
${env_common_esp32.build_flags}
20+
${raw_crsf_backpack_common.build_flags}
21+
-D PIN_BUTTON=0
22+
23+
[env:Raw_CRSF_ESP32_Backpack_via_WIFI]
24+
extends = env:Raw_CRSF_ESP32_Backpack_via_UART
25+
26+
[env:Raw_CRSF_ESP32C3_Backpack_via_UART]
27+
extends = env_common_esp32c3, raw_crsf_backpack_common
28+
build_flags =
29+
${env_common_esp32c3.build_flags}
30+
${raw_crsf_backpack_common.build_flags}
31+
-D PIN_BUTTON=9
32+
33+
[env:Raw_CRSF_ESP32C3_Backpack_via_WIFI]
34+
extends = env:Raw_CRSF_ESP32C3_Backpack_via_UART
35+
36+
[env:Raw_CRSF_ESP32S3_Backpack_via_UART]
37+
extends = env_common_esp32s3, raw_crsf_backpack_common
38+
build_flags =
39+
${env_common_esp32s3.build_flags}
40+
${raw_crsf_backpack_common.build_flags}
41+
-D PIN_BUTTON=0
42+
43+
[env:Raw_CRSF_ESP32S3_Backpack_via_WIFI]
44+
extends = env:Raw_CRSF_ESP32S3_Backpack_via_UART

0 commit comments

Comments
 (0)