Skip to content

Commit

Permalink
Merge branch 'master' into update-OTA_VERSION_ID-to-V4
Browse files Browse the repository at this point in the history
  • Loading branch information
JyeSmith committed Sep 21, 2024
2 parents dd46cd2 + e875cec commit 3ccddac
Show file tree
Hide file tree
Showing 21 changed files with 240 additions and 100 deletions.
5 changes: 3 additions & 2 deletions .github/workflows/build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -193,8 +193,9 @@ jobs:
exit 0
fi
aws s3api head-object --endpoint-url $AWS_ENDPOINT_URL --bucket expresslrs --key ExpressLRS/$GITHUB_SHA/firmware.zip > /dev/null || NOT_EXIST=true
if [ $NOT_EXIST ]; then
aws s3api head-object --endpoint-url $AWS_ENDPOINT_URL --bucket expresslrs --key ExpressLRS/$GITHUB_SHA/firmware.zip > /dev/null || ALLOW_UPLOAD=true
git describe --tags --exact-match HEAD && ALLOW_UPLOAD=true
if [ $ALLOW_UPLOAD ]; then
echo "Uploading firmware to artifactory"
aws s3 cp --endpoint-url $AWS_ENDPOINT_URL firmware.zip s3://expresslrs/ExpressLRS/$GITHUB_SHA/firmware.zip
Expand Down
3 changes: 3 additions & 0 deletions src/include/targets.h
Original file line number Diff line number Diff line change
Expand Up @@ -289,6 +289,9 @@ extern bool pwmSerialDefined;
#endif

#if defined(TARGET_UNIFIED_TX) || defined(TARGET_UNIFIED_RX)
#if defined(PLATFORM_ESP32)
#include <soc/uart_pins.h>
#endif
#if !defined(U0RXD_GPIO_NUM)
#define U0RXD_GPIO_NUM (3)
#endif
Expand Down
55 changes: 40 additions & 15 deletions src/lib/Backpack/devBackpack.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,9 @@ extern bool headTrackingEnabled;
bool TxBackpackWiFiReadyToSend = false;
bool VRxBackpackWiFiReadyToSend = false;
bool HTEnableFlagReadyToSend = false;
bool BackpackTelemReadyToSend = false;

bool lastRecordingState = false;
uint8_t lastLinkMode; // will get set in start() and used in event()

#if defined(GPIO_PIN_BACKPACK_EN)

Expand Down Expand Up @@ -258,14 +258,20 @@ static void AuxStateToMSPOut()
#endif // USE_TX_BACKPACK
}

void crsfTelemToMSPOut(uint8_t *data)
void sendCRSFTelemetryToBackpack(uint8_t *data)
{
if (config.GetBackpackTlmEnabled() == 0)
if (config.GetBackpackTlmMode() == BACKPACK_TELEM_MODE_OFF)
{
// Backpack telem is off
return;
}

if (config.GetLinkMode() == TX_MAVLINK_MODE)
{
// Tx is in MAVLink mode, don't forward CRSF telemetry
return;
}

mspPacket_t packet;
packet.reset();
packet.makeCommand();
Expand All @@ -286,6 +292,30 @@ void crsfTelemToMSPOut(uint8_t *data)
MSP::sendPacket(&packet, TxBackpack); // send to tx-backpack as MSP
}

void sendMAVLinkTelemetryToBackpack(uint8_t *data)
{
if (config.GetBackpackTlmMode() == BACKPACK_TELEM_MODE_OFF)
{
// Backpack telem is off
return;
}

uint8_t count = data[1];
TxBackpack->write(data + CRSF_FRAME_NOT_COUNTED_BYTES, count);
}

void sendConfigToBackpack()
{
// Send any config values to the tx-backpack, as one key/value pair per MSP msg
mspPacket_t packet;
packet.reset();
packet.makeCommand();
packet.function = MSP_ELRS_BACKPACK_CONFIG;
packet.addByte(MSP_ELRS_BACKPACK_CONFIG_TLM_MODE); // Backpack tlm mode
packet.addByte(config.GetBackpackTlmMode());
MSP::sendPacket(&packet, TxBackpack); // send to tx-backpack as MSP
}

static void initialize()
{
#if defined(GPIO_PIN_BACKPACK_EN)
Expand All @@ -306,7 +336,6 @@ static void initialize()

static int start()
{
lastLinkMode = config.GetLinkMode();
if (OPT_USE_TX_BACKPACK)
{
return DURATION_IMMEDIATELY;
Expand Down Expand Up @@ -354,6 +383,12 @@ static int timeout()
BackpackHTFlagToMSPOut(headTrackingEnabled);
}

if (BackpackTelemReadyToSend && connectionState < MODE_STATES)
{
BackpackTelemReadyToSend = false;
sendConfigToBackpack();
}

return BACKPACK_TIMEOUT;
}

Expand All @@ -366,17 +401,7 @@ static int event()
digitalWrite(GPIO_PIN_BACKPACK_EN, config.GetBackpackDisable() ? LOW : HIGH);
}
#endif
#if !defined(PLATFORM_STM32)
// Update the backpack operating mode when the link mode changes
uint8_t newMode = config.GetLinkMode();
if (lastLinkMode != newMode)
{
uint8_t mavlinkOutputBuffer[MAVLINK_MAX_PACKET_LEN];
uint16_t len = buildMAVLinkELRSModeChange(newMode, mavlinkOutputBuffer);
TxBackpack->write(mavlinkOutputBuffer, len);
}
lastLinkMode = config.GetLinkMode();
#endif

return DURATION_IGNORE;
}

Expand Down
5 changes: 4 additions & 1 deletion src/lib/Backpack/devBackpack.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,10 @@
#include "device.h"

void checkBackpackUpdate();
void crsfTelemToMSPOut(uint8_t *data);
void sendCRSFTelemetryToBackpack(uint8_t *data);
void sendMAVLinkTelemetryToBackpack(uint8_t *data);

extern bool HTEnableFlagReadyToSend;
extern bool BackpackTelemReadyToSend;

extern device_t Backpack_device;
28 changes: 22 additions & 6 deletions src/lib/CONFIG/config.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -180,7 +180,7 @@ void TxConfig::Load()
if (nvs_get_u8(handle, "backpackdisable", &value8) == ESP_OK)
m_config.backpackDisable = value8;
if (nvs_get_u8(handle, "backpacktlmen", &value8) == ESP_OK)
m_config.backpackTlmEnabled = value8;
m_config.backpackTlmMode = value8;
}

for(unsigned i=0; i<CONFIG_TX_MODEL_CNT; i++)
Expand Down Expand Up @@ -339,7 +339,7 @@ TxConfig::Commit()
nvs_set_u8(handle, "fanthresh", m_config.powerFanThreshold);

nvs_set_u8(handle, "backpackdisable", m_config.backpackDisable);
nvs_set_u8(handle, "backpacktlmen", m_config.backpackTlmEnabled);
nvs_set_u8(handle, "backpacktlmen", m_config.backpackTlmMode);
nvs_set_u8(handle, "dvraux", m_config.dvrAux);
nvs_set_u8(handle, "dvrstartdelay", m_config.dvrStartDelay);
nvs_set_u8(handle, "dvrstopdelay", m_config.dvrStopDelay);
Expand Down Expand Up @@ -441,7 +441,6 @@ TxConfig::SetLinkMode(uint8_t linkMode)
{
m_model->tlm = TLM_RATIO_1_2;
m_model->switchMode = smHybridOr16ch; // Force Hybrid / 16ch/2 switch modes for mavlink
m_config.backpackTlmEnabled = false; // Disable backpack telemetry since it'd be MSP mixed with MAVLink
}
m_modified |= MODEL_CHANGED | MAIN_CHANGED;
}
Expand Down Expand Up @@ -577,11 +576,11 @@ TxConfig::SetBackpackDisable(bool backpackDisable)
}

void
TxConfig::SetBackpackTlmEnabled(bool enabled)
TxConfig::SetBackpackTlmMode(uint8_t mode)
{
if (m_config.backpackTlmEnabled != enabled)
if (m_config.backpackTlmMode != mode)
{
m_config.backpackTlmEnabled = enabled;
m_config.backpackTlmMode = mode;
m_modified |= MAIN_CHANGED;
}
}
Expand Down Expand Up @@ -1236,6 +1235,23 @@ void RxConfig::SetBindStorage(rx_config_bindstorage_t value)
}
}

void RxConfig::SetTargetSysId(uint8_t value)
{
if (m_config.targetSysId != value)
{
m_config.targetSysId = value;
m_modified = true;
}
}
void RxConfig::SetSourceSysId(uint8_t value)
{
if (m_config.sourceSysId != value)
{
m_config.sourceSysId = value;
m_modified = true;
}
}

void RxConfig::ReturnLoan()
{
if (IsOnLoan())
Expand Down
20 changes: 16 additions & 4 deletions src/lib/CONFIG/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,13 @@ typedef union {
uint32_t raw;
} tx_button_color_t;

typedef enum {
BACKPACK_TELEM_MODE_OFF,
BACKPACK_TELEM_MODE_ESPNOW,
BACKPACK_TELEM_MODE_WIFI,
BACKPACK_TELEM_MODE_BLUETOOTH,
} telem_mode_t;

typedef struct {
uint32_t version;
uint8_t vtxBand; // 0=Off, else band number
Expand All @@ -85,8 +92,7 @@ typedef struct {
uint8_t motionMode:2, // bool, but space for 2 more modes
dvrStopDelay:3,
backpackDisable:1, // bool, disable backpack via EN pin if available
backpackTlmEnabled:1, // bool, enable telemetry via ESPNOW from backpack
unused:1; // FUTURE available
backpackTlmMode:2; // 0=Off, 1=Fwd tlm via espnow, 2=fwd tlm via wifi 3=(FUTURE) bluetooth
uint8_t dvrStartDelay:3,
dvrAux:5;
tx_button_color_t buttonColors[2]; // FUTURE: TX RGB color / mode (sets color of TX, can be a static color or standard)
Expand Down Expand Up @@ -123,7 +129,7 @@ class TxConfig
uint8_t GetDvrStartDelay() const { return m_config.dvrStartDelay; }
uint8_t GetDvrStopDelay() const { return m_config.dvrStopDelay; }
bool GetBackpackDisable() const { return m_config.backpackDisable; }
bool GetBackpackTlmEnabled() const { return m_config.backpackTlmEnabled; }
uint8_t GetBackpackTlmMode() const { return m_config.backpackTlmMode; }
tx_button_color_t const *GetButtonActions(uint8_t button) const { return &m_config.buttonColors[button]; }
model_config_t const &GetModelConfig(uint8_t model) const { return m_config.model_config[model]; }
uint8_t GetPTRStartChannel() const { return m_model->ptrStartChannel; }
Expand Down Expand Up @@ -153,7 +159,7 @@ class TxConfig
void SetDvrStopDelay(uint8_t dvrStopDelay);
void SetButtonActions(uint8_t button, tx_button_color_t actions[2]);
void SetBackpackDisable(bool backpackDisable);
void SetBackpackTlmEnabled(bool enabled);
void SetBackpackTlmMode(uint8_t mode);
void SetPTRStartChannel(uint8_t ptrStartChannel);
void SetPTREnableChannel(uint8_t ptrEnableChannel);

Expand Down Expand Up @@ -229,6 +235,8 @@ typedef struct __attribute__((packed)) {
uint8_t teamraceChannel:4,
teamracePosition:3,
teamracePitMode:1; // FUTURE: Enable pit mode when disabling model
uint8_t targetSysId;
uint8_t sourceSysId;
} rx_config_t;

class RxConfig
Expand Down Expand Up @@ -263,6 +271,8 @@ class RxConfig
uint8_t GetTeamraceChannel() const { return m_config.teamraceChannel; }
uint8_t GetTeamracePosition() const { return m_config.teamracePosition; }
eFailsafeMode GetFailsafeMode() const { return (eFailsafeMode)m_config.failsafeMode; }
uint8_t GetTargetSysId() const { return m_config.targetSysId; }
uint8_t GetSourceSysId() const { return m_config.sourceSysId; }
rx_config_bindstorage_t GetBindStorage() const { return (rx_config_bindstorage_t)m_config.bindStorage; }
bool IsOnLoan() const;

Expand All @@ -287,6 +297,8 @@ class RxConfig
void SetTeamraceChannel(uint8_t teamraceChannel);
void SetTeamracePosition(uint8_t teamracePosition);
void SetFailsafeMode(eFailsafeMode failsafeMode);
void SetTargetSysId(uint8_t sysID);
void SetSourceSysId(uint8_t sysID);
void SetBindStorage(rx_config_bindstorage_t value);
void ReturnLoan();

Expand Down
2 changes: 1 addition & 1 deletion src/lib/Handset/AutoDetect.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@

#include <driver/rmt.h>

constexpr auto RMT_TICKS_PER_US = 10;
constexpr auto RMT_TICKS_PER_US = 4;

void AutoDetect::Begin()
{
Expand Down
2 changes: 1 addition & 1 deletion src/lib/Handset/PPMHandset.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@

#include <driver/rmt.h>

constexpr auto RMT_TICKS_PER_US = 10;
constexpr auto RMT_TICKS_PER_US = 4;

void PPMHandset::Begin()
{
Expand Down
4 changes: 4 additions & 0 deletions src/lib/LED/devLED.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,9 @@ static const uint8_t *_durations;
static uint8_t _count;
static uint8_t _counter = 0;
static bool hasRGBLeds = false;
#if defined(TARGET_TX)
static bool hasGBLeds = false;
#endif

static uint16_t updateLED()
{
Expand Down Expand Up @@ -141,6 +143,7 @@ static int timeout()
return updateLED();
}

#if !defined(TARGET_RX)
static void setPowerLEDs()
{
if (hasGBLeds)
Expand All @@ -166,6 +169,7 @@ static void setPowerLEDs()
}
}
}
#endif

static int event()
{
Expand Down
44 changes: 44 additions & 0 deletions src/lib/LUA/rx_devLUA.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,29 @@ static struct luaItem_selection luaSBUSFailsafeMode = {
STR_EMPTYSPACE
};

static struct luaItem_int8 luaTargetSysId = {
{"Target SysID", CRSF_UINT8},
{
{
(uint8_t)1, // value - default to 1
(uint8_t)1, // min
(uint8_t)255, // max
}
},
STR_EMPTYSPACE
};
static struct luaItem_int8 luaSourceSysId = {
{"Source SysID", CRSF_UINT8},
{
{
(uint8_t)255, // value - default to 255
(uint8_t)1, // min
(uint8_t)255, // max
}
},
STR_EMPTYSPACE
};

#if defined(POWER_OUTPUT_VALUES)
static struct luaItem_selection luaTlmPower = {
{"Tlm Power", CRSF_TEXT_SELECTION},
Expand Down Expand Up @@ -510,6 +533,23 @@ static void registerLuaParameters()
config.SetFailsafeMode((eFailsafeMode)arg);
});

eSerialProtocol prot0 = config.GetSerialProtocol();
bool hasMavlink = prot0 == PROTOCOL_MAVLINK;
#if defined(PLATFORM_ESP32)
eSerial1Protocol prot1 = config.GetSerial1Protocol();
hasMavlink = hasMavlink || (prot1 == PROTOCOL_MAVLINK);
#endif

if (hasMavlink)
{
registerLUAParameter(&luaTargetSysId, [](struct luaPropertiesCommon* item, uint8_t arg){
config.SetTargetSysId((uint8_t)arg);
});
registerLUAParameter(&luaSourceSysId, [](struct luaPropertiesCommon* item, uint8_t arg){
config.SetSourceSysId((uint8_t)arg);
});
}

if (GPIO_PIN_ANT_CTRL != UNDEF_PIN)
{
registerLUAParameter(&luaAntennaMode, [](struct luaPropertiesCommon* item, uint8_t arg){
Expand Down Expand Up @@ -627,6 +667,10 @@ static int event()
}
setLuaTextSelectionValue(&luaBindStorage, config.GetBindStorage());
updateBindModeLabel();

setLuaUint8Value(&luaSourceSysId, config.GetSourceSysId() == 0 ? 255 : config.GetSourceSysId()); //display Source sysID if 0 display 255 to mimic logic in SerialMavlink.cpp
setLuaUint8Value(&luaTargetSysId, config.GetTargetSysId() == 0 ? 1 : config.GetTargetSysId()); //display Target sysID if 0 display 1 to mimic logic in SerialMavlink.cpp

return DURATION_IMMEDIATELY;
}

Expand Down
Loading

0 comments on commit 3ccddac

Please sign in to comment.