Skip to content

Commit

Permalink
Fix MSP and make timeout dynamic
Browse files Browse the repository at this point in the history
Add parameters to status bar

Use async and await on serial_backend
  • Loading branch information
haslinghuis committed Jun 26, 2022
1 parent 863dd3a commit 54d9f51
Show file tree
Hide file tree
Showing 5 changed files with 101 additions and 110 deletions.
63 changes: 39 additions & 24 deletions src/js/msp.js
Expand Up @@ -50,6 +50,10 @@ const MSP = {
packet_error: 0,
unsupported: 0,

MIN_TIMEOUT: 250,
MAX_TIMEOUT: 2000,
timeout: 250,

last_received_timestamp: null,
listeners: [],

Expand Down Expand Up @@ -318,25 +322,27 @@ const MSP = {
if (callback_msp) {
callback_msp();
}
return;
return false;
}

if (code === undefined || !serial.connectionId) {
return;
}

let bufferOut;
if (code <= 254) {
bufferOut = this.encode_message_v1(code, data);
} else {
bufferOut = this.encode_message_v2(code, data);
return false;
}

const obj = {'code': code, 'requestBuffer': bufferOut, 'callback': callback_msp ? callback_msp : false, 'timer': false, 'callbackOnError': doCallbackOnError};
const bufferOut = code <= 254 ? this.encode_message_v1(code, data) : this.encode_message_v2(code, data);
const obj = {
'code': code,
'requestBuffer': bufferOut,
'callback': callback_msp ? callback_msp : false,
'timer': false,
'callbackOnError': doCallbackOnError,
'start': performance.now(),
};

let requestExists = false;
for (const value of MSP.callbacks) {
if (value.code === code) {

for (const instance of MSP.callbacks) {
if (instance.code === code) {
// request already exist, we will just attach
requestExists = true;
break;
Expand All @@ -345,18 +351,26 @@ const MSP = {

if (!requestExists) {
obj.timer = setInterval(function () {
console.warn(`MSP: data request timed-out: ${code} ID: ${serial.connectionId} TAB: ${GUI.active_tab}`);
console.warn(`MSP: data request timed-out: ${code} ID: ${serial.connectionId} TAB: ${GUI.active_tab} TIMEOUT: ${MSP.timeout}`);
serial.send(bufferOut, function (_sendInfo) {
obj.stop = performance.now();
const executionTime = Math.round(obj.stop - obj.start);
MSP.timeout = Math.max(MSP.MIN_TIMEOUT, Math.min(executionTime, MSP.MAX_TIMEOUT));
});

serial.send(bufferOut, false);
}, 1000); // we should be able to define timeout in the future
}, MSP.timeout);
}

MSP.callbacks.push(obj);

// always send messages with data payload (even when there is a message already in the queue)
if (data || !requestExists) {
if (MSP.timeout > MSP.MIN_TIMEOUT) {
MSP.timeout--;
}

serial.send(bufferOut, function (sendInfo) {
if (sendInfo.bytesSent == bufferOut.byteLength) {
if (sendInfo.bytesSent === bufferOut.byteLength) {
if (callback_sent) {
callback_sent();
}
Expand All @@ -370,17 +384,18 @@ const MSP = {
/**
* resolves: {command: code, data: data, length: message_length}
*/
promise: function(code, data) {
const self = this;
return new Promise(function(resolve) {
self.send_message(code, data, false, function(_data) {
resolve(_data);
promise: async function(code, data) {
const self = this;

return new Promise(function(resolve) {
self.send_message(code, data, false, function(_data) {
resolve(_data);
});
});
});
},
callbacks_cleanup: function () {
for (let index = 0; index < this.callbacks.length; index++) {
clearInterval(this.callbacks[index].timer);
for (const callback of this.callbacks) {
clearInterval(callback.timer);
}

this.callbacks = [];
Expand Down
18 changes: 7 additions & 11 deletions src/js/msp/MSPHelper.js
Expand Up @@ -147,8 +147,6 @@ MspHelper.prototype.process_data = function(dataHandler) {
FC.CONFIG.mode = data.readU32();
FC.CONFIG.profile = data.readU8();

TABS.pid_tuning.checkUpdateProfile(false);

sensor_status(FC.CONFIG.activeSensors);
break;
case MSPCodes.MSP_STATUS_EX:
Expand All @@ -173,8 +171,6 @@ MspHelper.prototype.process_data = function(dataHandler) {
FC.CONFIG.armingDisableCount = data.readU8(); // Flag count
FC.CONFIG.armingDisableFlags = data.readU32();
}

TABS.pid_tuning.checkUpdateProfile(true);
}

sensor_status(FC.CONFIG.activeSensors);
Expand Down Expand Up @@ -274,10 +270,10 @@ MspHelper.prototype.process_data = function(dataHandler) {
FC.ANALOG.mAhdrawn = data.readU16();
FC.ANALOG.rssi = data.readU16(); // 0-1023
FC.ANALOG.amperage = data.read16() / 100; // A
FC.ANALOG.last_received_timestamp = Date.now();
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_41)) {
FC.ANALOG.voltage = data.readU16() / 100;
}
FC.ANALOG.last_received_timestamp = Date.now();
break;
case MSPCodes.MSP_VOLTAGE_METERS:
FC.VOLTAGE_METERS = [];
Expand Down Expand Up @@ -727,7 +723,6 @@ MspHelper.prototype.process_data = function(dataHandler) {
}
break;
case MSPCodes.MSP_SET_MOTOR:
console.log('Motor Speeds Updated');
break;
case MSPCodes.MSP_UID:
FC.CONFIG.uid[0] = data.readU32();
Expand Down Expand Up @@ -1728,8 +1723,8 @@ MspHelper.prototype.process_data = function(dataHandler) {
if (self.mspMultipleCache.length > 0) {

const partialBuffer = [];
for (let i = 0; i < self.mspMultipleCache.length; i++) {
partialBuffer.push8(self.mspMultipleCache[i]);
for (const instance of self.mspMultipleCache) {
partialBuffer.push8(instance);
}

MSP.send_message(MSPCodes.MSP_MULTIPLE_MSP, partialBuffer, false, dataHandler.callbacks);
Expand All @@ -1746,11 +1741,12 @@ MspHelper.prototype.process_data = function(dataHandler) {
console.log(`Unknown code detected: ${code}`);
} else {
console.log(`FC reports unsupported message error: ${code}`);
}

if (code === MSPCodes.MSP_SET_REBOOT) {
TABS.onboard_logging.mscRebootFailedCallback();
}
if (code === MSPCodes.MSP_SET_REBOOT) {
TABS.onboard_logging.mscRebootFailedCallback();
}

} else {
console.warn(`code: ${code} - crc failed`);
}
Expand Down
121 changes: 49 additions & 72 deletions src/js/serial_backend.js
Expand Up @@ -491,7 +491,7 @@ function connectCli() {
$('#tabs .tab_cli a').click();
}

function onConnect() {
async function onConnect() {
if ($('div#flashbutton a.flash_state').hasClass('active') && $('div#flashbutton a.flash').hasClass('active')) {
$('div#flashbutton a.flash_state').removeClass('active');
$('div#flashbutton a.flash').removeClass('active');
Expand Down Expand Up @@ -532,13 +532,12 @@ function onConnect() {

$('#tabs ul.mode-connected').show();

MSP.send_message(MSPCodes.MSP_FEATURE_CONFIG, false, false);
await MSP.promise(MSPCodes.MSP_FEATURE_CONFIG);
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_33)) {
MSP.send_message(MSPCodes.MSP_BATTERY_CONFIG, false, false);
await MSP.promise(MSPCodes.MSP_BATTERY_CONFIG);
}
MSP.send_message(MSPCodes.MSP_STATUS_EX, false, false);
MSP.send_message(MSPCodes.MSP_DATAFLASH_SUMMARY, false, false);

await MSP.promise(semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_32) ? MSPCodes.MSP_STATUS_EX : MSPCodes.MSP_STATUS);
await MSP.promise(MSPCodes.MSP_DATAFLASH_SUMMARY);
if (FC.CONFIG.boardType == 0 || FC.CONFIG.boardType == 2) {
startLiveDataRefreshTimer();
}
Expand Down Expand Up @@ -686,10 +685,10 @@ function have_sensor(sensors_detected, sensor_code) {

function startLiveDataRefreshTimer() {
// live data refresh
GUI.timeout_add('data_refresh', function () { update_live_status(); }, 100);
GUI.timeout_add('data_refresh', update_live_status, 100);
}

function update_live_status() {
async function update_live_status() {

const statuswrapper = $('#quad-status_wrapper');

Expand All @@ -698,75 +697,54 @@ function update_live_status() {
});

if (GUI.active_tab !== 'cli' && GUI.active_tab !== 'presets') {
MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false);
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_32)) {
MSP.send_message(MSPCodes.MSP_STATUS_EX, false, false);
} else {
MSP.send_message(MSPCodes.MSP_STATUS, false, false);
}
MSP.send_message(MSPCodes.MSP_ANALOG, false, false);
}
await MSP.promise(MSPCodes.MSP_BOXNAMES);
await MSP.promise(semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_32) ? MSPCodes.MSP_STATUS_EX : MSPCodes.MSP_STATUS);
await MSP.promise(MSPCodes.MSP_ANALOG);

const active = ((Date.now() - FC.ANALOG.last_received_timestamp) < 300);
const active = ((Date.now() - FC.ANALOG.last_received_timestamp) < 300);

for (let i = 0; i < FC.AUX_CONFIG.length; i++) {
if (FC.AUX_CONFIG[i] === 'ARM') {
if (bit_check(FC.CONFIG.mode, i)) {
$(".armedicon").addClass('active');
} else {
$(".armedicon").removeClass('active');
for (let i = 0; i < FC.AUX_CONFIG.length; i++) {
if (FC.AUX_CONFIG[i] === 'ARM') {
$(".armedicon").toggleClass('active', bit_check(FC.CONFIG.mode, i));
}
}
if (FC.AUX_CONFIG[i] === 'FAILSAFE') {
if (bit_check(FC.CONFIG.mode, i)) {
$(".failsafeicon").addClass('active');
} else {
$(".failsafeicon").removeClass('active');
if (FC.AUX_CONFIG[i] === 'FAILSAFE') {
$(".failsafeicon").toggleClass('active', bit_check(FC.CONFIG.mode, i));
}
}
}

if (FC.ANALOG != undefined) {
let nbCells = Math.floor(FC.ANALOG.voltage / FC.BATTERY_CONFIG.vbatmaxcellvoltage) + 1;
if (FC.ANALOG != undefined) {
let nbCells = Math.floor(FC.ANALOG.voltage / FC.BATTERY_CONFIG.vbatmaxcellvoltage) + 1;

if (FC.ANALOG.voltage == 0) {
nbCells = 1;
}
if (FC.ANALOG.voltage == 0) {
nbCells = 1;
}

const min = FC.BATTERY_CONFIG.vbatmincellvoltage * nbCells;
const max = FC.BATTERY_CONFIG.vbatmaxcellvoltage * nbCells;
const warn = FC.BATTERY_CONFIG.vbatwarningcellvoltage * nbCells;

const NO_BATTERY_VOLTAGE_MAXIMUM = 1.8; // Maybe is better to add a call to MSP_BATTERY_STATE but is not available for all versions

if (FC.ANALOG.voltage < min && FC.ANALOG.voltage > NO_BATTERY_VOLTAGE_MAXIMUM) {
$(".battery-status").addClass('state-empty').removeClass('state-ok').removeClass('state-warning');
$(".battery-status").css({
width: "100%",
});
} else {
$(".battery-status").css({
width: `${((FC.ANALOG.voltage - min) / (max - min) * 100)}%`,
});

if (FC.ANALOG.voltage < warn) {
$(".battery-status").addClass('state-warning').removeClass('state-empty').removeClass('state-ok');
} else {
$(".battery-status").addClass('state-ok').removeClass('state-warning').removeClass('state-empty');
}
}
const min = FC.BATTERY_CONFIG.vbatmincellvoltage * nbCells;
const max = FC.BATTERY_CONFIG.vbatmaxcellvoltage * nbCells;
const warn = FC.BATTERY_CONFIG.vbatwarningcellvoltage * nbCells;

}
const NO_BATTERY_VOLTAGE_MAXIMUM = 1.8; // Maybe is better to add a call to MSP_BATTERY_STATE but is not available for all versions

if (active) {
$(".linkicon").addClass('active');
} else {
$(".linkicon").removeClass('active');
}
if (FC.ANALOG.voltage < min && FC.ANALOG.voltage > NO_BATTERY_VOLTAGE_MAXIMUM) {
$(".battery-status").addClass('state-empty').removeClass('state-ok').removeClass('state-warning');
$(".battery-status").css({ width: "100%" });
} else {
$(".battery-status").css({ width: `${((FC.ANALOG.voltage - min) / (max - min) * 100)}%` });

statuswrapper.show();
GUI.timeout_remove('data_refresh');
startLiveDataRefreshTimer();
if (FC.ANALOG.voltage < warn) {
$(".battery-status").addClass('state-warning').removeClass('state-empty').removeClass('state-ok');
} else {
$(".battery-status").addClass('state-ok').removeClass('state-warning').removeClass('state-empty');
}
}
}

$(".linkicon").toggleClass('active', active);

statuswrapper.show();
GUI.timeout_remove('data_refresh');
startLiveDataRefreshTimer();
}
}

function specificByte(num, pos) {
Expand Down Expand Up @@ -846,15 +824,14 @@ function reinitializeConnection(originatorTab, callback) {
let attempts = 0;
const reconnect = setInterval(waitforSerial, 100);

function waitforSerial() {
async function waitforSerial() {
if (connectionTimestamp !== previousTimeStamp && CONFIGURATOR.connectionValid) {
console.log(`Serial connection available after ${attempts / 10} seconds`);
clearInterval(reconnect);
MSP.promise(MSPCodes.MSP_STATUS).then(() => {
GUI.log(i18n.getMessage('deviceReady'));
originatorTab.initialize(false, $('#content').scrollTop());
callback?.();
});
await MSP.promise(MSPCodes.MSP_STATUS);
GUI.log(i18n.getMessage('deviceReady'));
originatorTab.initialize(false, $('#content').scrollTop());
callback?.();
} else {
attempts++;
if (attempts > 100) {
Expand Down
8 changes: 5 additions & 3 deletions src/js/tabs/motors.js
Expand Up @@ -585,9 +585,11 @@ TABS.motors.initialize = async function (callback) {

// Amperage
function power_data_pull() {
motorVoltage.text(i18n.getMessage('motorsVoltageValue', [FC.ANALOG.voltage]));
motorMahDrawingElement.text(i18n.getMessage('motorsADrawingValue', [FC.ANALOG.amperage.toFixed(2)]));
motorMahDrawnElement.text(i18n.getMessage('motorsmAhDrawnValue', [FC.ANALOG.mAhdrawn]));
if (FC.ANALOG.last_received_timestamp) {
motorVoltage.text(i18n.getMessage('motorsVoltageValue', [FC.ANALOG.voltage]));
motorMahDrawingElement.text(i18n.getMessage('motorsADrawingValue', [FC.ANALOG.amperage.toFixed(2)]));
motorMahDrawnElement.text(i18n.getMessage('motorsmAhDrawnValue', [FC.ANALOG.mAhdrawn]));
}
}

GUI.interval_add('motors_power_data_pull_slow', power_data_pull, 250, true); // 4 fps
Expand Down
1 change: 1 addition & 0 deletions src/js/tabs/pid_tuning.js
Expand Up @@ -1436,6 +1436,7 @@ TABS.pid_tuning.initialize = function (callback) {
function process_html() {
TABS.pid_tuning.isHtmlProcessing = true;
FC.FEATURE_CONFIG.features.generateElements($('.tab-pid_tuning .features'));
self.checkUpdateProfile(false);

if (semver.lt(FC.CONFIG.apiVersion, "1.16.0") || semver.gte(FC.CONFIG.apiVersion, "1.20.0")) {
$('.tab-pid_tuning .pidTuningSuperexpoRates').hide();
Expand Down

0 comments on commit 54d9f51

Please sign in to comment.