Skip to content
Open
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
29 changes: 29 additions & 0 deletions hardware/targets.json
Original file line number Diff line number Diff line change
Expand Up @@ -581,5 +581,34 @@
"platform": "esp32-s3"
}
}
},
"raw-crsf": {
"name": "Raw CRSF Backpack",
"aat": {
"esp82": {
"product_name": "Generic ESP8285 / ESP8266 Receiver",
"firmware": "Raw_CRSF_ESP8285_Backpack",
"upload_methods": ["uart", "wifi"],
"platform": "esp8285"
},
"esp32": {
"product_name": "Generic ESP32 Receiver",
"firmware": "Raw_CRSF_ESP32_Backpack",
"upload_methods": ["uart", "wifi"],
"platform": "esp32"
},
"esp32c3": {
"product_name": "Generic ESP32C3 Receiver",
"firmware": "Raw_CRSF_ESP32C3_Backpack",
"upload_methods": ["uart", "wifi"],
"platform": "esp32-c3"
},
"esp32s3": {
"product_name": "Generic ESP32S3 Receiver",
"firmware": "Raw_CRSF_ESP32S3_Backpack",
"upload_methods": ["uart", "wifi"],
"platform": "esp32-s3"
}
}
}
}
1 change: 1 addition & 0 deletions platformio.ini
Original file line number Diff line number Diff line change
Expand Up @@ -16,3 +16,4 @@ extra_configs =
targets/rx5808.ini
targets/skyzone.ini
targets/mfd_crossbow.ini
targets/raw_crsf.ini
5 changes: 5 additions & 0 deletions src/Vrx_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,8 @@
#include "module_aat.h"
#elif defined(CROSSBOW_BACKPACK)
#include "mfd_crossbow.h"
#elif defined(RAW_CRSF_BACKPACK)
#include "raw_crsf.h"
#endif

/////////// DEFINES ///////////
Expand Down Expand Up @@ -124,6 +126,8 @@ VrxBackpackConfig config;
AatModule vrxModule(Serial);
#elif defined(CROSSBOW_BACKPACK)
MFDCrossbow vrxModule(&Serial);
#elif defined(RAW_CRSF_BACKPACK)
CRSFBackPack vrxModule(&Serial);
#endif

/////////// FUNCTION DEFS ///////////
Expand Down Expand Up @@ -259,6 +263,7 @@ void ProcessMSPPacket(mspPacket_t *packet)
DBGLN("CRSF_TLM packet too short")
break;
}
vrxModule.SendRawTelemetry(packet->payload, packet->payloadSize);
switch (packet->payload[2]) {
case CRSF_FRAMETYPE_GPS:
vrxModule.SendGpsTelemetry((crsf_packet_gps_t *)packet->payload);
Expand Down
5 changes: 5 additions & 0 deletions src/module_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,11 @@ ModuleBase::SendBatteryTelemetry(uint8_t *rawCrsfPacket)
{
}

void
ModuleBase::SendRawTelemetry(uint8_t *rawCrsfPacket, uint16_t size)
{
}

void
ModuleBase::Loop(uint32_t now)
{
Expand Down
1 change: 1 addition & 0 deletions src/module_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ class ModuleBase
void SendLinkTelemetry(uint8_t *rawCrsfPacket);
void SendBatteryTelemetry(uint8_t *rawCrsfPacket);
void SendGpsTelemetry(crsf_packet_gps_t *packet) {}
void SendRawTelemetry(uint8_t *rawCrsfPacket, uint16_t size);
void Loop(uint32_t now);
};

Expand Down
29 changes: 29 additions & 0 deletions src/raw_crsf.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
#include "raw_crsf.h"

CRSFBackPack::CRSFBackPack(HardwareSerial *port) :
m_port(port),
lastSent(0),
lastUpdated(0)
{
}

void
CRSFBackPack::SendRawTelemetry(uint8_t *rawCrsfPacket, uint16_t size)
{
lastUpdated = millis();
m_port->write(rawCrsfPacket, size);
}

void
CRSFBackPack::Loop(uint32_t now)
{
ModuleBase::Loop(now);

// If the GPS data is <= 10 seconds old, keep spamming it out at 10hz
bool gpsIsValid = (now < lastUpdated + 10000);

if (now > lastSent + 100 && gpsIsValid)
{
lastSent = now;
}
}
23 changes: 23 additions & 0 deletions src/raw_crsf.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
#pragma once

#include "module_base.h"
#include "msptypes.h"

#define VRX_UART_BAUD 115200

class CRSFBackPack : public ModuleBase
{
public:
CRSFBackPack(HardwareSerial *port);
void SendRawTelemetry(uint8_t *rawCrsfPacket, uint16_t size);
void Loop(uint32_t now);

private:
void SendHeartbeat();
void SendGpsRawInt();
void SendGlobalPositionInt();

HardwareSerial *m_port;
uint32_t lastSent;
uint32_t lastUpdated;
};
33 changes: 32 additions & 1 deletion targets/common.ini
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,7 @@ build_src_filter =
-<orqa.*>
-<Timer_main.cpp>
-<mfd_crossbow.*>
-<raw_crsf.*>

# ------------------------- COMMON RAPIDFIRE-BACKPACK DEFINITIONS -----------------
[rapidfire_vrx_backpack_common]
Expand All @@ -115,6 +116,7 @@ build_src_filter =
-<orqa.*>
-<Timer_main.cpp>
-<mfd_crossbow.*>
-<raw_crsf.*>

# ------------------------- COMMON RX5808-BACKPACK DEFINITIONS -----------------
[rx5808_vrx_backpack_common]
Expand All @@ -135,6 +137,7 @@ build_src_filter =
-<orqa.*>
-<Timer_main.cpp>
-<mfd_crossbow.*>
-<raw_crsf.*>

# ------------------------- COMMON STEADYVIEW-BACKPACK DEFINITIONS -----------------
[steadyview_vrx_backpack_common]
Expand All @@ -155,6 +158,7 @@ build_src_filter =
-<orqa.*>
-<Timer_main.cpp>
-<mfd_crossbow.*>
-<raw_crsf.*>

# ------------------------- COMMON FUSION-BACKPACK DEFINITIONS -----------------
[fusion_vrx_backpack_common]
Expand All @@ -175,6 +179,7 @@ build_src_filter =
-<orqa.*>
-<Timer_main.cpp>
-<mfd_crossbow.*>
-<raw_crsf.*>

# ------------------------- COMMON HDZERO-BACKPACK DEFINITIONS -----------------
[hdzero_vrx_backpack_common]
Expand All @@ -195,6 +200,7 @@ build_src_filter =
-<orqa.*>
-<Timer_main.cpp>
-<mfd_crossbow.*>
-<raw_crsf.*>

# ------------------------- COMMON SKYZONE-MSP-BACKPACK DEFINITIONS -----------------
[skyzone_msp_vrx_backpack_common]
Expand All @@ -215,6 +221,7 @@ build_src_filter =
-<orqa.*>
-<Timer_main.cpp>
-<mfd_crossbow.*>
-<raw_crsf.*>

# ------------------------- COMMON ORQA-BACKPACK DEFINITIONS -------------------
[orqa_backpack_common]
Expand All @@ -235,6 +242,7 @@ build_src_filter =
; -<orqa.*>
-<Timer_main.cpp>
-<mfd_crossbow.*>
-<raw_crsf.*>

# ------------------------- COMMON TIMER-BACKPACK DEFINITIONS -----------------
[timer_backpack_common]
Expand All @@ -254,6 +262,7 @@ build_src_filter =
-<orqa.*>
; -<Timer_main.cpp>
-<mfd_crossbow.*>
-<raw_crsf.*>

# ------------------------- COMMON MFD-CROSSBOW-BACKPACK DEFINITIONS -----------------
[mfd_crossbow_backpack_common]
Expand All @@ -274,6 +283,28 @@ build_src_filter =
-<orqa.*>
-<Timer_main.cpp>
; -<mfd_crossbow.*>
-<raw_crsf.*>
lib_deps =
${env.lib_deps}
${common_env_data.mavlink_lib_dep}
${common_env_data.mavlink_lib_dep}

# ------------------------- COMMON RAW-CRSF-BACKPACK DEFINITIONS -----------------
[raw_crsf_backpack_common]
build_flags =
${common_env_data.build_flags}
-D TARGET_VRX_BACKPACK
-D RAW_CRSF_BACKPACK
build_src_filter =
${common_env_data.build_src_filter}
-<Tx_main.cpp>
; -<Vrx_main.cpp>
-<rapidfire.*>
-<rx5808.*>
-<steadyview.*>
-<fusion.*>
-<hdzero.*>
-<skyzone_msp.*>
-<orqa.*>
-<Timer_main.cpp>
-<mfd_crossbow.*>
; -<raw_crsf.*>
44 changes: 44 additions & 0 deletions targets/raw_crsf.ini
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
# ********************************
# MFD Crossbow tracker backpack
# ********************************

[env:Raw_CRSF_ESP8285_Backpack_via_UART]
extends = env_common_esp8285, raw_crsf_backpack_common
build_flags =
${env_common_esp8285.build_flags}
${raw_crsf_backpack_common.build_flags}
-D PIN_BUTTON=0
-D PIN_LED=16

[env:Raw_CRSF_ESP8285_Backpack_via_WIFI]
extends = env:Raw_CRSF_ESP8285_Backpack_via_UART

[env:Raw_CRSF_ESP32_Backpack_via_UART]
extends = env_common_esp32, raw_crsf_backpack_common
build_flags =
${env_common_esp32.build_flags}
${raw_crsf_backpack_common.build_flags}
-D PIN_BUTTON=0

[env:Raw_CRSF_ESP32_Backpack_via_WIFI]
extends = env:Raw_CRSF_ESP32_Backpack_via_UART

[env:Raw_CRSF_ESP32C3_Backpack_via_UART]
extends = env_common_esp32c3, raw_crsf_backpack_common
build_flags =
${env_common_esp32c3.build_flags}
${raw_crsf_backpack_common.build_flags}
-D PIN_BUTTON=9

[env:Raw_CRSF_ESP32C3_Backpack_via_WIFI]
extends = env:Raw_CRSF_ESP32C3_Backpack_via_UART

[env:Raw_CRSF_ESP32S3_Backpack_via_UART]
extends = env_common_esp32s3, raw_crsf_backpack_common
build_flags =
${env_common_esp32s3.build_flags}
${raw_crsf_backpack_common.build_flags}
-D PIN_BUTTON=0

[env:Raw_CRSF_ESP32S3_Backpack_via_WIFI]
extends = env:Raw_CRSF_ESP32S3_Backpack_via_UART