Skip to content

Commit

Permalink
Merge branch 'master' into more-baros
Browse files Browse the repository at this point in the history
  • Loading branch information
CapnBry committed Mar 29, 2024
2 parents 7fa180c + 7eb760f commit 6bc003f
Show file tree
Hide file tree
Showing 21 changed files with 314 additions and 94 deletions.
7 changes: 4 additions & 3 deletions src/html/index.html
Original file line number Diff line number Diff line change
Expand Up @@ -142,12 +142,13 @@ <h2>Firmware Update</h2>
If this happens you will need to recover via USB/Serial. You may also download the
<a href="firmware.bin" title="Click to download firmware">currently running firmware</a>.
<br/><br/>
<button id="upload_btn" class="mui-btn mui-btn--primary upload">
<button id="upload_btn" class="mui-btn mui-btn--primary upload" style="margin: 0 auto; display:block;">
<label>
Flash firmware file
<input type="file" id="firmware_file" name="update" />
Select firmware file
<input type="file" id="firmware_file" name="update[]" />
</label>
</button>
<div id="filedrag">or drop firmware file here</div>
<br/>
<h3 id="status"></h3>
<progress id="progressBar" value="0" max="100" style="width:100%;"></progress>
Expand Down
36 changes: 29 additions & 7 deletions src/html/scan.js
Original file line number Diff line number Diff line change
Expand Up @@ -251,6 +251,7 @@ function init() {
// Start on the options tab
mui.tabs.activate('pane-justified-1');
@@end
initFiledrag();
initOptions();
}

Expand Down Expand Up @@ -435,10 +436,36 @@ _('network-tab').addEventListener('mui.tabs.showstart', getNetworks);

// =========================================================

function uploadFile() {
function initFiledrag() {
const fileselect = _('firmware_file');
const filedrag = _('filedrag');

fileselect.addEventListener('change', fileSelectHandler, false);

const xhr = new XMLHttpRequest();
if (xhr.upload) {
filedrag.addEventListener('dragover', fileDragHover, false);
filedrag.addEventListener('dragleave', fileDragHover, false);
filedrag.addEventListener('drop', fileSelectHandler, false);
filedrag.style.display = 'block';
}
}

function fileDragHover(e) {
e.stopPropagation();
e.preventDefault();
if (e.target === _('filedrag')) e.target.className = (e.type === 'dragover' ? 'hover' : '');
}

function fileSelectHandler(e) {
fileDragHover(e);
const files = e.target.files || e.dataTransfer.files;
uploadFile(files[0]);
}

function uploadFile(file) {
_('upload_btn').disabled = true
try {
const file = _('firmware_file').files[0];
const formdata = new FormData();
formdata.append('upload', file, file.name);
const ajax = new XMLHttpRequest();
Expand Down Expand Up @@ -553,11 +580,6 @@ function abortHandler(event) {
});
}

_('firmware_file').addEventListener('change', (e) => {
e.preventDefault();
uploadFile();
});

@@if isTX:
_('fileselect').addEventListener('change', (e) => {
const files = e.target.files || e.dataTransfer.files;
Expand Down
1 change: 1 addition & 0 deletions src/include/common.h
Original file line number Diff line number Diff line change
Expand Up @@ -268,6 +268,7 @@ uint8_t enumRatetoIndex(expresslrs_RFrates_e const eRate);

extern uint8_t UID[UID_LEN];
extern bool connectionHasModelMatch;
extern bool teamraceHasModelMatch;
extern bool InBindingMode;
extern uint8_t ExpressLRS_currTlmDenom;
extern connectionState_e connectionState;
Expand Down
20 changes: 20 additions & 0 deletions src/lib/CONFIG/config.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1023,6 +1023,8 @@ RxConfig::SetDefaults(bool commit)
SetPwmChannel(2, 0, 2, false, 0, false); // ch2 is throttle, failsafe it to 988
#endif

m_config.teamraceChannel = AUX7; // CH11

#if defined(RCVR_INVERT_TX)
m_config.serialProtocol = PROTOCOL_INVERTED_CRSF;
#else
Expand Down Expand Up @@ -1112,6 +1114,24 @@ void RxConfig::SetSerialProtocol(eSerialProtocol serialProtocol)
}
}

void RxConfig::SetTeamraceChannel(uint8_t teamraceChannel)
{
if (m_config.teamraceChannel != teamraceChannel)
{
m_config.teamraceChannel = teamraceChannel;
m_modified = true;
}
}

void RxConfig::SetTeamracePosition(uint8_t teamracePosition)
{
if (m_config.teamracePosition != teamracePosition)
{
m_config.teamracePosition = teamracePosition;
m_modified = true;
}
}

void RxConfig::SetFailsafeMode(eFailsafeMode failsafeMode)
{
if (m_config.failsafeMode != failsafeMode)
Expand Down
7 changes: 7 additions & 0 deletions src/lib/CONFIG/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -217,6 +217,9 @@ typedef struct __attribute__((packed)) {
failsafeMode:2,
unused:2;
rx_config_pwm_t pwmChannels[PWM_MAX_CHANNELS] __attribute__((aligned(4)));
uint8_t teamraceChannel:4,
teamracePosition:3,
teamracePitMode:1; // FUTURE: Enable pit mode when disabling model
} rx_config_t;

class RxConfig
Expand All @@ -241,6 +244,8 @@ class RxConfig
bool GetForceTlmOff() const { return m_config.forceTlmOff; }
uint8_t GetRateInitialIdx() const { return m_config.rateInitialIdx; }
eSerialProtocol GetSerialProtocol() const { return (eSerialProtocol)m_config.serialProtocol; }
uint8_t GetTeamraceChannel() const { return m_config.teamraceChannel; }
uint8_t GetTeamracePosition() const { return m_config.teamracePosition; }
eFailsafeMode GetFailsafeMode() const { return (eFailsafeMode)m_config.failsafeMode; }
bool GetVolatileBind() const { return m_config.volatileBind; }

Expand All @@ -259,6 +264,8 @@ class RxConfig
void SetForceTlmOff(bool forceTlmOff);
void SetRateInitialIdx(uint8_t rateInitialIdx);
void SetSerialProtocol(eSerialProtocol serialProtocol);
void SetTeamraceChannel(uint8_t teamraceChannel);
void SetTeamracePosition(uint8_t teamracePosition);
void SetFailsafeMode(eFailsafeMode failsafeMode);
void SetVolatileBind(bool value);

Expand Down
15 changes: 15 additions & 0 deletions src/lib/CrsfProtocol/crsf_protocol.h
Original file line number Diff line number Diff line change
Expand Up @@ -398,6 +398,21 @@ static inline uint16_t ICACHE_RAM_ATTR CRSF_to_N(uint16_t val, uint16_t cnt)
return (val - CRSF_CHANNEL_VALUE_1000) * cnt / (CRSF_CHANNEL_VALUE_2000 - CRSF_CHANNEL_VALUE_1000 + 1);
}

static inline uint8_t ICACHE_RAM_ATTR CRSF_to_SWITCH3b(uint16_t ch)
{
// AUX2-7 are Low Resolution, "7pos" 6+center (3-bit)
// The output is mapped evenly across 6 output values (0-5)
// with a special value 7 indicating the middle so it works
// with switches with a middle position as well as 6-position
const uint16_t CHANNEL_BIN_COUNT = 6;
const uint16_t CHANNEL_BIN_SIZE = (CRSF_CHANNEL_VALUE_MAX - CRSF_CHANNEL_VALUE_MIN) / CHANNEL_BIN_COUNT;
// If channel is within 1/4 a BIN of being in the middle use special value 7
if (ch < (CRSF_CHANNEL_VALUE_MID-CHANNEL_BIN_SIZE/4)
|| ch > (CRSF_CHANNEL_VALUE_MID+CHANNEL_BIN_SIZE/4))
return CRSF_to_N(ch, CHANNEL_BIN_COUNT);
return 7;
}

// 3b switches use 0-5 to represent 6 positions switches and "7" to represent middle
// The calculation is a bit non-linear all the way to the endpoints due to where
// Ardupilot defines its modes
Expand Down
14 changes: 8 additions & 6 deletions src/lib/DEVICE/device.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,12 +117,14 @@ void devicesTriggerEvent()

static int _devicesUpdate(unsigned long now)
{
int32_t core = CURRENT_CORE;

bool handleEvents = eventFired[core==-1?0:core] || lastConnectionState[core==-1?0:core] != connectionState || lastModelMatch[core==-1?0:core] != connectionHasModelMatch;
eventFired[core==-1?0:core] = false;
lastConnectionState[core==-1?0:core] = connectionState;
lastModelMatch[core==-1?0:core] = connectionHasModelMatch;
const int32_t core = CURRENT_CORE;
const int32_t coreMulti = (core == -1) ? 0 : core;

bool newModelMatch = connectionHasModelMatch && teamraceHasModelMatch;
bool handleEvents = eventFired[coreMulti] || lastConnectionState[coreMulti] != connectionState || lastModelMatch[coreMulti] != newModelMatch;
eventFired[coreMulti] = false;
lastConnectionState[coreMulti] = connectionState;
lastModelMatch[coreMulti] = newModelMatch;

for(size_t i=0 ; i<deviceCount ; i++)
{
Expand Down
1 change: 0 additions & 1 deletion src/lib/Handset/AutoDetect.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@

#include <driver/rmt.h>

constexpr rmt_channel_t PPM_RMT_CHANNEL = RMT_CHANNEL_0;
constexpr auto RMT_TICKS_PER_US = 10;

void AutoDetect::Begin()
Expand Down
10 changes: 8 additions & 2 deletions src/lib/Handset/PPMHandset.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@

#include <driver/rmt.h>

constexpr rmt_channel_t PPM_RMT_CHANNEL = RMT_CHANNEL_0;
constexpr auto RMT_TICKS_PER_US = 10;

void PPMHandset::Begin()
Expand Down Expand Up @@ -52,13 +51,20 @@ void PPMHandset::handleInput()
if (items)
{
length /= 4; // one RMT = 4 Bytes
numChannels = length;
int channelCount = 0;
for (int i = 0; i < length; i++)
{
const auto item = items[i];
// Stop if there is a 0 duration
if (item.duration0 == 0 || item.duration1 == 0)
{
break;
}
channelCount ++;
const auto ppm = (item.duration0 + item.duration1) / RMT_TICKS_PER_US;
ChannelData[i] = fmap(ppm, 988, 2012, CRSF_CHANNEL_VALUE_MIN, CRSF_CHANNEL_VALUE_MAX);
}
numChannels = channelCount;
vRingbufferReturnItem(rb, static_cast<void *>(items));
lastPPM = now;
}
Expand Down
8 changes: 7 additions & 1 deletion src/lib/Handset/PPMHandset.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,4 +15,10 @@ class PPMHandset final : public Handset
uint32_t lastPPM = 0;
size_t numChannels = 0;
RingbufHandle_t rb = nullptr;
};
};

#if defined(PLATFORM_ESP32_S3)
constexpr rmt_channel_t PPM_RMT_CHANNEL = RMT_CHANNEL_4;
#else
constexpr rmt_channel_t PPM_RMT_CHANNEL = RMT_CHANNEL_0;
#endif
6 changes: 3 additions & 3 deletions src/lib/LED/devLED.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -205,13 +205,13 @@ static int event()

if (GPIO_PIN_LED != UNDEF_PIN)
{
if (connectionHasModelMatch)
if (!connectionHasModelMatch || !teamraceHasModelMatch)
{
digitalWrite(GPIO_PIN_LED, HIGH ^ GPIO_LED_RED_INVERTED); // turn on led
return flashLED(GPIO_PIN_LED, GPIO_LED_RED_INVERTED, LEDSEQ_MODEL_MISMATCH, sizeof(LEDSEQ_MODEL_MISMATCH));
}
else
{
return flashLED(GPIO_PIN_LED, GPIO_LED_RED_INVERTED, LEDSEQ_MODEL_MISMATCH, sizeof(LEDSEQ_MODEL_MISMATCH));
digitalWrite(GPIO_PIN_LED, HIGH ^ GPIO_LED_RED_INVERTED); // turn on led
}
}
#endif
Expand Down
2 changes: 1 addition & 1 deletion src/lib/LED/devRGB.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -457,7 +457,7 @@ static int timeout()
{
case connected:
#if defined(TARGET_RX)
if (!connectionHasModelMatch)
if (!connectionHasModelMatch || !teamraceHasModelMatch)
{
blinkyColor.h = 10;
return flashLED(blinkyColor, 192, 0, LEDSEQ_MODEL_MISMATCH, sizeof(LEDSEQ_MODEL_MISMATCH));
Expand Down
31 changes: 31 additions & 0 deletions src/lib/LUA/rx_devLUA.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,24 @@ static struct luaItem_selection luaDiversityMode = {
};
#endif

static struct luaItem_folder luaTeamraceFolder = {
{"Team Race", CRSF_FOLDER},
};

static struct luaItem_selection luaTeamraceChannel = {
{"Channel", CRSF_TEXT_SELECTION},
0, // value
"AUX2;AUX3;AUX4;AUX5;AUX6;AUX7;AUX8;AUX9;AUX10;AUX11;AUX12",
STR_EMPTYSPACE
};

static struct luaItem_selection luaTeamracePosition = {
{"Position", CRSF_TEXT_SELECTION},
0, // value
"Disabled;1/Low;2;3;Mid;4;5;6/High",
STR_EMPTYSPACE
};

//----------------------------Info-----------------------------------

static struct luaItem_string luaModelNumber = {
Expand Down Expand Up @@ -375,6 +393,15 @@ static void registerLuaParameters()
registerLUAParameter(&luaTlmPower, &luaparamSetPower);
#endif

// Teamrace
registerLUAParameter(&luaTeamraceFolder);
registerLUAParameter(&luaTeamraceChannel, [](struct luaPropertiesCommon* item, uint8_t arg) {
config.SetTeamraceChannel(arg + AUX2);
}, luaTeamraceFolder.common.id);
registerLUAParameter(&luaTeamracePosition, [](struct luaPropertiesCommon* item, uint8_t arg) {
config.SetTeamracePosition(arg);
}, luaTeamraceFolder.common.id);

#if defined(GPIO_PIN_PWM_OUTPUTS)
if (OPT_HAS_SERVO_OUTPUT)
{
Expand Down Expand Up @@ -426,6 +453,10 @@ static int event()
setLuaTextSelectionValue(&luaTlmPower, luaPwrVal - POWERMGNT::getMinPower());
#endif

// Teamrace
setLuaTextSelectionValue(&luaTeamraceChannel, config.GetTeamraceChannel() - AUX2);
setLuaTextSelectionValue(&luaTeamracePosition, config.GetTeamracePosition());

#if defined(GPIO_PIN_PWM_OUTPUTS)
if (OPT_HAS_SERVO_OUTPUT)
{
Expand Down
16 changes: 1 addition & 15 deletions src/lib/OTA/OTA.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,21 +143,7 @@ void ICACHE_RAM_ATTR GenerateChannelDataHybrid8(OTA_Packet_s * const otaPktPtr,
if (bitclearedSwitchIndex == 6)
value = CRSF_to_N(channelData[6 + 1 + 4], 16);
else
{
// AUX2-7 are Low Resolution, "7pos" 6+center (3-bit)
// The output is mapped evenly across 6 output values (0-5)
// with a special value 7 indicating the middle so it works
// with switches with a middle position as well as 6-position
const uint16_t CHANNEL_BIN_COUNT = 6;
const uint16_t CHANNEL_BIN_SIZE = (CRSF_CHANNEL_VALUE_MAX - CRSF_CHANNEL_VALUE_MIN) / CHANNEL_BIN_COUNT;
uint16_t ch = channelData[bitclearedSwitchIndex + 1 + 4];
// If channel is within 1/4 a BIN of being in the middle use special value 7
if (ch < (CRSF_CHANNEL_VALUE_MID-CHANNEL_BIN_SIZE/4)
|| ch > (CRSF_CHANNEL_VALUE_MID+CHANNEL_BIN_SIZE/4))
value = CRSF_to_N(ch, CHANNEL_BIN_COUNT);
else
value = 7;
} // If not 16-pos
value = CRSF_to_SWITCH3b(channelData[bitclearedSwitchIndex + 1 + 4]);

ota4->rc.switches =
TelemetryStatus << 6 |
Expand Down
12 changes: 5 additions & 7 deletions src/lib/PWM/PWM_ESP8266.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,15 +43,13 @@ void PWMController::setDuty(pwm_channel_t channel, uint16_t duty)
void PWMController::setMicroseconds(pwm_channel_t channel, uint16_t microseconds)
{
int8_t pin = pwm_gpio[channel];
if (microseconds > 0) {
startWaveform8266(pin, microseconds, refreshInterval[channel] - microseconds);
}
else {
// startWaveform8266 does not handle 0 properly, there's still a 1.2 microsecond pulse
// so we have to explicitly stop the waveform generation
if (microseconds == 0 || microseconds==refreshInterval[channel])
{
stopWaveform8266(pin);
digitalWrite(pin, LOW);
digitalWrite(pin, microseconds == 0 ? HIGH : LOW);
return;
}
startWaveform8266(pin, microseconds, refreshInterval[channel] - microseconds);
}

#endif
Loading

0 comments on commit 6bc003f

Please sign in to comment.