1
0
Fork 0
mirror of https://github.com/iNavFlight/inav-configurator.git synced 2025-07-23 16:25:19 +03:00
This commit is contained in:
Andi Kanzler 2024-02-10 18:08:17 -03:00
parent 939f5af04b
commit f24ccfc637
96 changed files with 16438 additions and 8058 deletions

View file

@ -5,7 +5,7 @@ var appUpdater = appUpdater || {};
appUpdater.checkRelease = function (currVersion) {
var modalStart;
$.get('https://api.github.com/repos/iNavFlight/inav-configurator/releases', function (releaseData) {
GUI.log(chrome.i18n.getMessage('loadedReleaseInfo'));
GUI.log(localization.getMessage('loadedReleaseInfo'));
//Git return sorted list, 0 - last release
let newVersion = releaseData[0].tag_name;
@ -15,7 +15,7 @@ appUpdater.checkRelease = function (currVersion) {
GUI.log(newVersion, chrome.runtime.getManifest().version);
GUI.log(currVersion);
GUI.log(chrome.i18n.getMessage('newVersionAvailable'));
GUI.log(localization.getMessage('newVersionAvailable'));
modalStart = new jBox('Modal', {
width: 400,
height: 200,

View file

@ -10,7 +10,7 @@ const ConnectionType = {
class Connection {
constructor() {
this._connectionId = false;
this._connectionId = 0;
this._openRequested = false;
this._openCanceled = false;
this._bitrate = 0;
@ -145,7 +145,6 @@ class Connection {
} else {
this._openRequested = false;
console.log('Failed to open');
googleAnalytics.sendException('FailedToOpen', false);
if (callback) {
callback(false);
}
@ -163,13 +162,11 @@ class Connection {
this.removeAllListeners();
this.disconnectImplementation(result => {
this.checkChromeLastError();
if (result) {
console.log('Connection with ID: ' + this._connectionId + ' closed, Sent: ' + this._bytesSent + ' bytes, Received: ' + this._bytesReceived + ' bytes');
} else {
console.log('Failed to close connection with ID: ' + this._connectionId + ' closed, Sent: ' + this._bytesSent + ' bytes, Received: ' + this._bytesReceived + ' bytes');
googleAnalytics.sendException('Connection: FailedToClose', false);
}
this._connectionId = false;
@ -240,12 +237,6 @@ class Connection {
}
}
checkChromeLastError() {
if (chrome.runtime.lastError) {
console.error(chrome.runtime.lastError.message);
}
}
addOnReceiveCallback(callback) {
throw new TypeError("Abstract method");
}

View file

@ -59,7 +59,7 @@ class ConnectionBle extends Connection {
await this.openDevice()
.then(() => {
this.addOnReceiveErrorListener(error => {
GUI.log(chrome.i18n.getMessage('connectionBleInterrupted'));
GUI.log(localization.getMessage('connectionBleInterrupted'));
this.abort();
});
@ -71,7 +71,7 @@ class ConnectionBle extends Connection {
});
}
}).catch(error => {
GUI.log(chrome.i18n.getMessage('connectionBleError', [error]));
GUI.log(localization.getMessage('connectionBleError', [error]));
if (callback) {
callback(false);
}
@ -119,7 +119,7 @@ class ConnectionBle extends Connection {
return device.gatt.connect()
.then(server => {
console.log("Connect to: " + device.name);
GUI.log(chrome.i18n.getMessage('connectionConnected', [device.name]));
GUI.log(localization.getMessage('connectionConnected', [device.name]));
return server.getPrimaryServices();
}).then(services => {
let connectedService = services.find(service => {
@ -131,7 +131,7 @@ class ConnectionBle extends Connection {
throw new Error("Unsupported device (service UUID mismatch).");
}
GUI.log(chrome.i18n.getMessage('connectionBleType', [this._deviceDescription.name]));
GUI.log(localization.getMessage('connectionBleType', [this._deviceDescription.name]));
return connectedService.getCharacteristics();
}).then(characteristics => {
characteristics.forEach(characteristic => {

View file

@ -1,139 +1,103 @@
'use strict'
const { SerialPortStream } = require('@serialport/stream');
const { autoDetect } = require('@serialport/bindings-cpp')
const binding = autoDetect();
class ConnectionSerial extends Connection {
constructor() {
super();
this._failed = 0;
this._serialport = null;
this._errorListeners = [];
this._onReceiveListeners = [];
this._onErrorListener = [];
}
connectImplementation(path, options, callback) {
chrome.serial.connect(path, options, (connectionInfo) => {
this.checkChromeLastError();
if (connectionInfo && !this._openCanceled) {
this.addOnReceiveErrorListener(info => {
console.error(info);
googleAnalytics.sendException('Serial: ' + info.error, false);
switch (info.error) {
case 'system_error': // we might be able to recover from this one
if (!this._failed++) {
chrome.serial.setPaused(this._connectionId, false, function () {
SerialCom.getInfo((info) => {
if (info) {
if (!info.paused) {
console.log('SERIAL: Connection recovered from last onReceiveError');
googleAnalytics.sendException('Serial: onReceiveError - recovered', false);
this._failed = 0;
} else {
console.log('SERIAL: Connection did not recover from last onReceiveError, disconnecting');
GUI.log(chrome.i18n.getMessage('serialPortUnrecoverable'));
googleAnalytics.sendException('Serial: onReceiveError - unrecoverable', false);
this.abort();
}
} else {
this.checkChromeLastError();
}
});
});
}
break;
case 'break': // This occurs on F1 boards with old firmware during reboot
case 'overrun':
case 'frame_error': //Got disconnected
// wait 50 ms and attempt recovery
var error = info.error;
setTimeout(() => {
chrome.serial.setPaused(info.connectionId, false, function() {
SerialCom.getInfo(function (info) {
if (info) {
if (info.paused) {
// assume unrecoverable, disconnect
console.log('SERIAL: Connection did not recover from ' + error + ' condition, disconnecting');
GUI.log(chrome.i18n.getMessage('serialPortUnrecoverable'));;
googleAnalytics.sendException('Serial: ' + error + ' - unrecoverable', false);
this.abort();
} else {
console.log('SERIAL: Connection recovered from ' + error + ' condition');
googleAnalytics.sendException('Serial: ' + error + ' - recovered', false);
}
}
});
});
}, 50);
break;
case 'timeout':
// TODO
break;
case 'device_lost':
case 'disconnected':
default:
this.abort();
}
connectImplementation(path, options, callback) {
this._serialport = new SerialPortStream({binding, path: path, baudRate: options.bitrate, autoOpen: true}, () => {
this._serialport.on('data', buffer => {
this._onReceiveListeners.forEach(listener => {
listener({
connectionId: this._connectionId,
data: buffer
});
});
GUI.log(chrome.i18n.getMessage('connectionConnected', [path]));
}
})
this._serialport.on('error', error => {
console.log("Serial error: " + error);
this._onReceiveErrorListeners.forEach(listener => {
listener(error);
});
});
if (callback) {
callback(connectionInfo);
callback({
connectionId: ++this._connectionId,
bitrate: options.bitrate
});
}
});
}
disconnectImplementation(callback) {
chrome.serial.disconnect(this._connectionId, (result) => {
if (callback) {
callback(result);
}
});
if (this._serialport && this._serialport.isOpen) {
this._serialport.close(error => {
if (error) {
console.log("Unable to close serial: " + error)
}
if (callback) {
callback(error ? false : true);
}
});
}
}
sendImplementation(data, callback) {
chrome.serial.send(this._connectionId, data, callback);
}
addOnReceiveCallback(callback){
chrome.serial.onReceive.addListener(callback);
}
removeOnReceiveCallback(callback){
chrome.serial.onReceive.removeListener(callback);
}
addOnReceiveErrorCallback(callback) {
chrome.serial.onReceiveError.addListener(callback);
}
removeOnReceiveErrorCallback(callback) {
chrome.serial.onReceiveError.removeListener(callback);
}
static getDevices(callback) {
chrome.serial.getDevices((devices_array) => {
var devices = [];
devices_array.forEach((device) => {
devices.push(device.path);
});
callback(devices);
this._serialport.write(Buffer.from(data), error => {
var result = 0;
if (error) {
result = 1;
console.log("Serial wrire error: " + error)
}
if (callback) {
callback({
bytesSent: data.byteLength,
resultCode: result
});
}
});
}
static getInfo(connectionId, callback) {
chrome.serial.getInfo(connectionId, callback);
addOnReceiveCallback(callback){
this._onReceiveErrorListeners.push(callback);
}
static getControlSignals(connectionId, callback) {
chrome.serial.getControlSignals(connectionId, callback);
removeOnReceiveCallback(callback){
this._onReceiveListeners = this._onReceiveErrorListeners.filter(listener => listener !== callback);
}
static setControlSignals(connectionId, signals, callback) {
chrome.serial.setControlSignals(connectionId, signals, callback);
addOnReceiveErrorCallback(callback) {
this._onReceiveErrorListeners.push(callback);
}
removeOnReceiveErrorCallback(callback) {
this._onReceiveErrorListeners = this._onReceiveErrorListeners.filter(listener => listener !== callback);
}
static async getDevices(callback) {
SerialPort.list().then((ports, error) => {
var devices = [];
if (error) {
GUI.log("Unable to list serial ports.");
} else {
ports.forEach(port => {
devices.push(port.path);
});
}
if (callback)
callback(devices);
});
}
}

View file

@ -43,7 +43,6 @@ class ConnectionTcp extends Connection {
this.addOnReceiveErrorListener(info => {
console.error(info);
googleAnalytics.sendException('TCP: ' + info.error, false);
let message;
switch (info.resultCode) {
@ -79,7 +78,7 @@ class ConnectionTcp extends Connection {
this.abort();
});
GUI.log(chrome.i18n.getMessage('connectionConnected', ["tcp://" + this._connectionIP + ":" + this._connectionPort]));
GUI.log(localization.getMessage('connectionConnected', ["tcp://" + this._connectionIP + ":" + this._connectionPort]));
if (callback) {
callback({

View file

@ -46,7 +46,7 @@ class ConnectionUdp extends Connection {
this._timeoutId = setTimeout(() => {
if (!this._isCli) { // Disable timeout for CLI
GUI.log(chrome.i18n.getMessage('connectionUdpTimeout'));
GUI.log(localization.getMessage('connectionUdpTimeout'));
this.abort();
}
}, 10000);
@ -55,7 +55,6 @@ class ConnectionUdp extends Connection {
// Actually useless, but according to chrome documentation also UDP triggers error events ¯\_(ツ)_/¯
this.addOnReceiveErrorListener(info => {
console.error(info);
googleAnalytics.sendException('UDP: ' + info.error, false);
let message;
switch (info.resultCode) {
@ -91,7 +90,7 @@ class ConnectionUdp extends Connection {
this.abort();
});
GUI.log(chrome.i18n.getMessage('connectionConnected', ["udp://" + this._connectionIP + ":" + this._connectionPort]));
GUI.log(localization.getMessage('connectionConnected', ["udp://" + this._connectionIP + ":" + this._connectionPort]));
if (callback) {
callback({

View file

@ -3,7 +3,7 @@
var CONFIGURATOR = {
// all versions are specified and compared using semantic versioning http://semver.org/
'minfirmwareVersionAccepted': '7.0.0',
'maxFirmwareVersionAccepted': '9.0.0', // Condition is < (lt) so we accept all in 8.x branch
'maxFirmwareVersionAccepted': '8.0.0', // Condition is < (lt) so we accept all in 7.x branch
'connectionValid': false,
'connectionValidCliOnly': false,
'cliActive': false,

View file

@ -39,44 +39,48 @@ helper.defaultsDialog = (function () {
value: "DSHOT300"
},
/*
Ez Tune setup
Filtering
*/
{
key: "ez_enabled",
value: "ON"
},
{
key: "ez_filter_hz",
key: "gyro_main_lpf_hz",
value: 90
},
{
key: "ez_axis_ratio",
value: 116
key: "gyro_main_lpf_type",
value: "PT1"
},
{
key: "ez_response",
value: 71
key: "dterm_lpf_hz",
value: 85
},
{
key: "ez_damping",
value: 103
key: "dterm_lpf_type",
value: "PT3"
},
{
key: "ez_stability",
value: 105
key: "dynamic_gyro_notch_enabled",
value: "ON"
},
{
key: "ez_aggressiveness",
value: 100
key: "dynamic_gyro_notch_q",
value: 250
},
{
key: "ez_rate",
value: 134
key: "dynamic_gyro_notch_min_hz",
value: 70
},
{
key: "ez_expo",
value: 118
key: "setpoint_kalman_enabled",
value: "ON"
},
{
key: "setpoint_kalman_q",
value: 200
},
{
key: "smith_predictor_delay", // Enable Smith Predictor
value: 1.5
},
/*
Mechanics
*/
@ -108,6 +112,64 @@ helper.defaultsDialog = (function () {
key: "antigravity_accelerator",
value: 5
},
/*
Rates
*/
{
key: "rc_yaw_expo",
value: 75
},
{
key: "rc_expo",
value: 75
},
{
key: "roll_rate",
value: 70
},
{
key: "pitch_rate",
value: 70
},
{
key: "yaw_rate",
value: 60
},
/*
PIDs
*/
{
key: "mc_p_pitch",
value: 32
},
{
key: "mc_i_pitch",
value: 90
},
{
key: "mc_d_pitch",
value: 25
},
{
key: "mc_p_roll",
value: 28
},
{
key: "mc_i_roll",
value: 80
},
{
key: "mc_d_roll",
value: 23
},
{
key: "mc_p_yaw",
value: 30
},
{
key: "mc_i_yaw",
value: 80
},
/*
* TPA
*/
@ -130,6 +192,11 @@ helper.defaultsDialog = (function () {
{
key: "failsafe_procedure",
value: "DROP"
},
// Ez Tune
{
key: "ez_filter_hz",
value: 90
}
]
},
@ -160,43 +227,15 @@ helper.defaultsDialog = (function () {
value: "DSHOT300"
},
/*
Ez Tune setup
Filtering
*/
{
key: "ez_enabled",
value: "ON"
},
{
key: "ez_filter_hz",
key: "gyro_main_lpf_hz",
value: 110
},
{
key: "ez_axis_ratio",
value: 110
},
{
key: "ez_response",
value: 92
},
{
key: "ez_damping",
value: 108
},
{
key: "ez_stability",
value: 110
},
{
key: "ez_aggressiveness",
value: 80
},
{
key: "ez_rate",
value: 134
},
{
key: "ez_expo",
value: 118
key: "gyro_main_lpf_type",
value: "PT1"
},
/*
Dynamic gyro LPF
@ -218,6 +257,41 @@ helper.defaultsDialog = (function () {
value: 3
},
/*
D-term
*/
{
key: "dterm_lpf_hz",
value: 110
},
{
key: "dterm_lpf_type",
value: "PT3"
},
{
key: "dynamic_gyro_notch_enabled",
value: "ON"
},
{
key: "dynamic_gyro_notch_q",
value: 250
},
{
key: "dynamic_gyro_notch_min_hz",
value: 100
},
{
key: "setpoint_kalman_enabled",
value: "ON"
},
{
key: "setpoint_kalman_q",
value: 200
},
{
key: "smith_predictor_delay", // Enable Smith Predictor
value: 1.5
},
/*
Mechanics
*/
{
@ -248,6 +322,64 @@ helper.defaultsDialog = (function () {
key: "antigravity_accelerator",
value: 5
},
/*
Rates
*/
{
key: "rc_yaw_expo",
value: 75
},
{
key: "rc_expo",
value: 75
},
{
key: "roll_rate",
value: 70
},
{
key: "pitch_rate",
value: 70
},
{
key: "yaw_rate",
value: 60
},
/*
PIDs
*/
{
key: "mc_p_pitch",
value: 40
},
{
key: "mc_i_pitch",
value: 90
},
{
key: "mc_d_pitch",
value: 27
},
{
key: "mc_p_roll",
value: 36
},
{
key: "mc_i_roll",
value: 80
},
{
key: "mc_d_roll",
value: 25
},
{
key: "mc_p_yaw",
value: 35
},
{
key: "mc_i_yaw",
value: 80
},
/*
* TPA
*/
@ -270,6 +402,11 @@ helper.defaultsDialog = (function () {
{
key: "failsafe_procedure",
value: "DROP"
},
// Ez Tune
{
key: "ez_filter_hz",
value: 110
}
]
},
@ -300,44 +437,52 @@ helper.defaultsDialog = (function () {
value: "DSHOT300"
},
/*
Ez Tune setup
Filtering
*/
{
key: "ez_enabled",
value: "ON"
},
{
key: "ez_filter_hz",
key: "gyro_main_lpf_hz",
value: 90
},
{
key: "ez_axis_ratio",
value: 110
key: "gyro_main_lpf_type",
value: "PT1"
},
{
key: "ez_response",
value: 101
key: "dterm_lpf_hz",
value: 80
},
{
key: "ez_damping",
value: 115
key: "dterm_lpf_type",
value: "PT3"
},
{
key: "ez_stability",
value: 100
key: "dynamic_gyro_notch_enabled",
value: "ON"
},
{
key: "ez_aggressiveness",
value: 100
key: "dynamic_gyro_notch_mode",
value: "3D"
},
{
key: "ez_rate",
value: 134
key: "dynamic_gyro_notch_q",
value: 250
},
{
key: "ez_expo",
value: 118
},
key: "dynamic_gyro_notch_min_hz",
value: 60
},
{
key: "setpoint_kalman_enabled",
value: "ON"
},
{
key: "setpoint_kalman_q",
value: 200
},
{
key: "smith_predictor_delay", // Enable Smith Predictor
value: 1.5
},
/*
Mechanics
*/
@ -369,6 +514,64 @@ helper.defaultsDialog = (function () {
key: "antigravity_accelerator",
value: 5
},
/*
Rates
*/
{
key: "rc_yaw_expo",
value: 75
},
{
key: "rc_expo",
value: 75
},
{
key: "roll_rate",
value: 70
},
{
key: "pitch_rate",
value: 70
},
{
key: "yaw_rate",
value: 60
},
/*
PIDs
*/
{
key: "mc_p_pitch",
value: 44
},
{
key: "mc_i_pitch",
value: 85
},
{
key: "mc_d_pitch",
value: 28
},
{
key: "mc_p_roll",
value: 40
},
{
key: "mc_i_roll",
value: 75
},
{
key: "mc_d_roll",
value: 26
},
{
key: "mc_p_yaw",
value: 40
},
{
key: "mc_i_yaw",
value: 80
},
/*
* TPA
*/
@ -391,6 +594,11 @@ helper.defaultsDialog = (function () {
{
key: "failsafe_procedure",
value: "DROP"
},
// Ez Tune
{
key: "ez_filter_hz",
value: 90
}
]
},
@ -924,7 +1132,7 @@ helper.defaultsDialog = (function () {
privateScope.finalize = function (selectedDefaultPreset) {
mspHelper.saveToEeprom(function () {
//noinspection JSUnresolvedVariable
GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
GUI.log(localization.getMessage('configurationEepromSaved'));
if (selectedDefaultPreset.reboot) {
GUI.tab_switch_cleanup(function () {
@ -933,7 +1141,7 @@ helper.defaultsDialog = (function () {
if (typeof savingDefaultsModal !== 'undefined') {
savingDefaultsModal.close();
}
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
GUI.log(localization.getMessage('deviceRebooting'));
GUI.handleReconnect();
});
});
@ -958,9 +1166,6 @@ helper.defaultsDialog = (function () {
miscSettings.push(input);
}
});
//Save analytics
googleAnalytics.sendEvent('Setting', 'Defaults', selectedDefaultPreset.title);
var settingsChainer = MSPChainerClass();
var chain = [];

View file

@ -29,7 +29,6 @@ var CONFIG,
MOTOR_DATA,
SERVO_DATA,
GPS_DATA,
ADSB_VEHICLES,
MISSION_PLANNER,
ANALOG,
ARMING_CONFIG,
@ -66,7 +65,8 @@ var CONFIG,
BOARD_ALIGNMENT,
CURRENT_METER_CONFIG,
FEATURES,
RATE_DYNAMICS;
RATE_DYNAMICS,
EZ_TUNE;
var FC = {
restartRequired: false,
@ -252,12 +252,6 @@ var FC = {
packetCount: 0
};
ADSB_VEHICLES = {
vehiclesCount: 0,
callsignLength: 0,
vehicles: []
};
MISSION_PLANNER = new WaypointCollection();
ANALOG = {
@ -1243,13 +1237,7 @@ var FC = {
operandType: "Set Flight Parameter",
hasOperand: [true, false],
output: "raw"
},
54: {
name: "Mag calibration",
operandType: "Set Flight Parameter",
hasOperand: [false, false],
output: "boolean"
},
},
}
},
getOperandTypes: function () {

View file

@ -183,7 +183,7 @@ GUI_control.prototype.content_ready = function (callback) {
const documentationDiv = $('<div>').addClass('cf_doc_version_bt');
$('<a>').attr('href', 'https://github.com/iNavFlight/inav/wiki')
.attr('target', '_blank').attr('id', 'button-documentation')
.html(chrome.i18n.getMessage('documentation')).appendTo(documentationDiv);
.html(localization.getMessage('documentation')).appendTo(documentationDiv);
documentationDiv.insertAfter(tabTitle);
// loading tooltip
@ -256,7 +256,7 @@ GUI_control.prototype.updateStatusBar = function() {
$('span.i2c-error').text(CONFIG.i2cError);
$('span.cycle-time').text(CONFIG.cycleTime);
$('span.cpu-load').text(chrome.i18n.getMessage('statusbar_cpu_load', [CONFIG.cpuload]));
$('span.cpu-load').text(localization.getMessage('statusbar_cpu_load', [CONFIG.cpuload]));
$('span.arming-flags').text(activeArmFlags.length ? activeArmFlags.join(', ') : '-');
};
@ -265,9 +265,9 @@ GUI_control.prototype.updateProfileChange = function(refresh) {
$('#profilechange').val(CONFIG.profile);
$('#batteryprofilechange').val(CONFIG.battery_profile);
if (refresh) {
GUI.log(chrome.i18n.getMessage('loadedMixerProfile', [CONFIG.mixer_profile + 1]));
GUI.log(chrome.i18n.getMessage('pidTuning_LoadedProfile', [CONFIG.profile + 1]));
GUI.log(chrome.i18n.getMessage('loadedBatteryProfile', [CONFIG.battery_profile + 1]));
GUI.log(localization.getMessage('loadedMixerProfile', [CONFIG.mixer_profile + 1]));
GUI.log(localization.getMessage('pidTuning_LoadedProfile', [CONFIG.profile + 1]));
GUI.log(localization.getMessage('loadedBatteryProfile', [CONFIG.battery_profile + 1]));
updateActivatedTab();
}
};
@ -379,7 +379,7 @@ GUI_control.prototype.renderOperandValue = function ($container, operandMetadata
GUI_control.prototype.renderLogicConditionSelect = function ($container, logicConditions, current, onChange, withAlways, onlyEnabled) {
let $select = $container.append('<select class="mix-rule-condition">').find("select"),
lcCount = logicConditions.getCount();
lcCount = logicConditions.getCount(),
option = "";
if (withAlways) {

View file

@ -548,14 +548,14 @@ Buffer.concat = function concat (list, length) {
var i
if (length === undefined) {
length = 0
for (i = 0; i < list.length; ++i) {
for (let i = 0; i < list.length; ++i) {
length += list[i].length
}
}
var buffer = Buffer.allocUnsafe(length)
var pos = 0
for (i = 0; i < list.length; ++i) {
for (let i = 0; i < list.length; ++i) {
var buf = list[i]
if (isInstance(buf, Uint8Array)) {
buf = Buffer.from(buf)
@ -922,7 +922,7 @@ function arrayIndexOf (arr, val, byteOffset, encoding, dir) {
var i
if (dir) {
var foundIndex = -1
for (i = byteOffset; i < arrLength; i++) {
for (let i = byteOffset; i < arrLength; i++) {
if (read(arr, i) === read(val, foundIndex === -1 ? 0 : i - foundIndex)) {
if (foundIndex === -1) foundIndex = i
if (i - foundIndex + 1 === valLength) return foundIndex * indexSize
@ -933,7 +933,7 @@ function arrayIndexOf (arr, val, byteOffset, encoding, dir) {
}
} else {
if (byteOffset + valLength > arrLength) byteOffset = arrLength - valLength
for (i = byteOffset; i >= 0; i--) {
for (let i = byteOffset; i >= 0; i--) {
var found = true
for (var j = 0; j < valLength; j++) {
if (read(arr, i + j) !== read(val, j)) {
@ -1759,7 +1759,7 @@ Buffer.prototype.fill = function fill (val, start, end, encoding) {
var i
if (typeof val === 'number') {
for (i = start; i < end; ++i) {
for (let i = start; i < end; ++i) {
this[i] = val
}
} else {
@ -1771,7 +1771,7 @@ Buffer.prototype.fill = function fill (val, start, end, encoding) {
throw new TypeError('The value "' + val +
'" is invalid for argument "value"')
}
for (i = 0; i < end - start; ++i) {
for (let i = 0; i < end - start; ++i) {
this[i + start] = bytes[i % len]
}
}
@ -2240,7 +2240,7 @@ EventEmitter.prototype.emit = function emit(type) {
// slower
default:
args = new Array(len - 1);
for (i = 1; i < len; i++)
for (let i = 1; i < len; i++)
args[i - 1] = arguments[i];
emitMany(handler, isFn, this, args);
}
@ -2399,7 +2399,7 @@ EventEmitter.prototype.removeListener =
} else if (typeof list !== 'function') {
position = -1;
for (i = list.length - 1; i >= 0; i--) {
for (let i = list.length - 1; i >= 0; i--) {
if (list[i] === listener || list[i].listener === listener) {
originalListener = list[i].listener;
position = i;
@ -2451,7 +2451,7 @@ EventEmitter.prototype.removeAllListeners =
if (arguments.length === 0) {
var keys = objectKeys(events);
var key;
for (i = 0; i < keys.length; ++i) {
for (let i = 0; i < keys.length; ++i) {
key = keys[i];
if (key === 'removeListener') continue;
this.removeAllListeners(key);
@ -2468,7 +2468,7 @@ EventEmitter.prototype.removeAllListeners =
this.removeListener(type, listeners);
} else if (listeners) {
// LIFO order
for (i = listeners.length - 1; i >= 0; i--) {
for (let i = listeners.length - 1; i >= 0; i--) {
this.removeListener(type, listeners[i]);
}
}
@ -5815,12 +5815,12 @@ module.exports = deprecate;
* Mark that a method should not be used.
* Returns a modified function which warns once by default.
*
* If `localStorage.noDeprecation = true` is set, then it is a no-op.
* If `localstore.noDeprecation = true` is set, then it is a no-op.
*
* If `localStorage.throwDeprecation = true` is set, then deprecated functions
* If `localstore.throwDeprecation = true` is set, then deprecated functions
* will throw an Error when invoked.
*
* If `localStorage.traceDeprecation = true` is set, then deprecated functions
* If `localstore.traceDeprecation = true` is set, then deprecated functions
* will invoke `console.trace()` instead of `console.error()`.
*
* @param {Function} fn - the function to deprecate
@ -7516,7 +7516,7 @@ function config (name) {
element.txt(obj);
}
} else if (Array.isArray(obj)) {
for (index in obj) {
for (let index in obj) {
if (!hasProp.call(obj, index)) continue;
child = obj[index];
for (key in child) {
@ -7542,7 +7542,7 @@ function config (name) {
element = element.txt(child);
}
} else if (Array.isArray(child)) {
for (index in child) {
for (let index in child) {
if (!hasProp.call(child, index)) continue;
entry = child[index];
if (typeof entry === 'string') {
@ -7686,7 +7686,7 @@ function config (name) {
processItem = function(processors, item, key) {
var i, len, process;
for (i = 0, len = processors.length; i < len; i++) {
for (let i = 0, len = processors.length; i < len; i++) {
process = processors[i];
item = process(item, key);
}
@ -7865,7 +7865,7 @@ function config (name) {
xpath = "/" + ((function() {
var i, len, results;
results = [];
for (i = 0, len = stack.length; i < len; i++) {
for (let i = 0, len = stack.length; i < len; i++) {
node = stack[i];
results.push(node["#name"]);
}
@ -8106,7 +8106,7 @@ function config (name) {
if (isFunction(Object.assign)) {
Object.assign.apply(null, arguments);
} else {
for (i = 0, len = sources.length; i < len; i++) {
for (let i = 0, len = sources.length; i < len; i++) {
source = sources[i];
if (source != null) {
for (key in source) {
@ -8819,12 +8819,12 @@ function config (name) {
value = value.valueOf();
}
if (Array.isArray(target)) {
for (i = 0, len = target.length; i < len; i++) {
for (let i = 0, len = target.length; i < len; i++) {
insTarget = target[i];
this.instruction(insTarget);
}
} else if (isObject(target)) {
for (insTarget in target) {
for (let insTarget in target) {
if (!hasProp.call(target, insTarget)) continue;
insValue = target[insTarget];
this.instruction(insTarget, insValue);
@ -9145,7 +9145,7 @@ function config (name) {
}
name = name.valueOf();
if (Array.isArray(name)) {
for (i = 0, len = name.length; i < len; i++) {
for (let i = 0, len = name.length; i < len; i++) {
attName = name[i];
delete this.attributes[attName];
}
@ -9396,7 +9396,7 @@ function config (name) {
this.instruction(insTarget);
}
} else if (isObject(target)) {
for (insTarget in target) {
for (let insTarget in target) {
if (!hasProp.call(target, insTarget)) continue;
insValue = target[insTarget];
this.instruction(insTarget, insValue);
@ -9446,7 +9446,7 @@ function config (name) {
doc = this.document();
doctype = new XMLDocType(doc, pubID, sysID);
ref1 = doc.children;
for (i = j = 0, len = ref1.length; j < len; i = ++j) {
for (let i = j = 0, len = ref1.length; j < len; i = ++j) {
child = ref1[i];
if (child instanceof XMLDocType) {
doc.children[i] = doctype;
@ -9454,7 +9454,7 @@ function config (name) {
}
}
ref2 = doc.children;
for (i = k = 0, len1 = ref2.length; k < len1; i = ++k) {
for (let i = k = 0, len1 = ref2.length; k < len1; i = ++k) {
child = ref2[i];
if (child.isRoot) {
doc.children.splice(i, 0, doctype);
@ -9722,7 +9722,7 @@ function config (name) {
XMLStreamWriter.prototype.document = function(doc) {
var child, i, j, len, len1, ref, ref1, results;
ref = doc.children;
for (i = 0, len = ref.length; i < len; i++) {
for (let i = 0, len = ref.length; i < len; i++) {
child = ref[i];
child.isLastRootNode = false;
}
@ -9790,7 +9790,7 @@ function config (name) {
this.stream.write(' [');
this.stream.write(this.endline(node));
ref = node.children;
for (i = 0, len = ref.length; i < len; i++) {
for (let i = 0, len = ref.length; i < len; i++) {
child = ref[i];
switch (false) {
case !(child instanceof XMLDTDAttList):
@ -9850,7 +9850,7 @@ function config (name) {
} else {
this.stream.write('>' + this.newline);
ref1 = node.children;
for (i = 0, len = ref1.length; i < len; i++) {
for (let i = 0, len = ref1.length; i < len; i++) {
child = ref1[i];
switch (false) {
case !(child instanceof XMLCData):
@ -10004,7 +10004,7 @@ function config (name) {
this.textispresent = false;
r = '';
ref = doc.children;
for (i = 0, len = ref.length; i < len; i++) {
for (let i = 0, len = ref.length; i < len; i++) {
child = ref[i];
r += (function() {
switch (false) {
@ -10068,7 +10068,7 @@ function config (name) {
r += ' [';
r += this.newline;
ref = node.children;
for (i = 0, len = ref.length; i < len; i++) {
for (let i = 0, len = ref.length; i < len; i++) {
child = ref[i];
r += (function() {
switch (false) {
@ -10133,7 +10133,7 @@ function config (name) {
} else {
if (this.dontprettytextnodes) {
ref1 = node.children;
for (i = 0, len = ref1.length; i < len; i++) {
for (let i = 0, len = ref1.length; i < len; i++) {
child = ref1[i];
if (child.value != null) {
this.textispresent++;

File diff suppressed because one or more lines are too long

File diff suppressed because it is too large Load diff

File diff suppressed because it is too large Load diff

6
js/libraries/three/three.min.js vendored Normal file

File diff suppressed because one or more lines are too long

View file

@ -1,73 +1,114 @@
'use strict';
function localize() {
var localized = 0;
const fs = require('fs')
var translate = function(messageID) {
let Localiziation = function(locale) {
let self = { };
let messages = null;
let localized = 0
let local = locale;
self.loadMessages = function () {
var data;
try {
data = fs.readFileSync(path.join(__dirname, "./locale/" + local + "/messages.json"), 'utf8',);
messages = JSON.parse(data);
} catch (err) {
console.log("Error while reading languge file");
}
}
self.getMessage = function(messageID, substitutions = null) {
try {
if (substitutions) {
return messages[messageID].message.replace(/\{(\d+)\}/g, function (t, i) {
return substitutions[i] !== void 0 ? substitutions[i] : "{" + (i - substitutions.length) + "}";
});
} else {
return messages[messageID].message;
}
} catch {
console.log("Unable to get messageID: " + messageID)
return messageID;
}
}
self.translate = function(messageID) {
localized++;
return chrome.i18n.getMessage(messageID);
if (messages == null) {
self.loadMessages();
}
return self.getMessage(messageID);
};
$('[i18n]:not(.i18n-replaced)').each(function() {
var element = $(this);
self.localize = function () {
$('[i18n]:not(.i18n-replaced)').each(function() {
var element = $(this);
element.html(translate(element.attr('i18n')));
element.addClass('i18n-replaced');
});
element.html(self.translate(element.attr('i18n')));
element.addClass('i18n-replaced');
});
$('[data-i18n]:not(.i18n-replaced)').each(function() {
var element = $(this);
$('[data-i18n]:not(.i18n-replaced)').each(function() {
var element = $(this);
const translated = translate(element.data('i18n'));
element.html(translated);
element.addClass('i18n-replaced');
if (element.attr("title") !== "") {
element.attr("title", translated);
}
});
const translated = self.translate(element.data('i18n'));
element.html(translated);
element.addClass('i18n-replaced');
if (element.attr("title") !== "") {
element.attr("title", translated);
}
});
$('[i18n_title]:not(.i18n_title-replaced)').each(function() {
var element = $(this);
$('[i18n_title]:not(.i18n_title-replaced)').each(function() {
var element = $(this);
element.attr('title', translate(element.attr('i18n_title')));
element.addClass('i18n_title-replaced');
});
element.attr('title', self.translate(element.attr('i18n_title')));
element.addClass('i18n_title-replaced');
});
$('[data-i18n_title]:not(.i18n_title-replaced)').each(function() {
var element = $(this);
$('[data-i18n_title]:not(.i18n_title-replaced)').each(function() {
var element = $(this);
element.attr('title', translate(element.data('i18n_title')));
element.addClass('i18n_title-replaced');
});
element.attr('title', self.translate(element.data('i18n_title')));
element.addClass('i18n_title-replaced');
});
$('[i18n_label]:not(.i18n_label-replaced)').each(function() {
var element = $(this);
$('[i18n_label]:not(.i18n_label-replaced)').each(function() {
var element = $(this);
element.attr('label', translate(element.attr('i18n_label')));
element.addClass('i18n_label-replaced');
});
element.attr('label', self.translate(element.attr('i18n_label')));
element.addClass('i18n_label-replaced');
});
$('[data-i18n_label]:not(.i18n_label-replaced)').each(function() {
var element = $(this);
$('[data-i18n_label]:not(.i18n_label-replaced)').each(function() {
var element = $(this);
element.attr('label', translate(element.data('i18n_label')));
element.addClass('i18n_label-replaced');
});
element.attr('label', self.translate(element.data('i18n_label')));
element.addClass('i18n_label-replaced');
});
$('[i18n_value]:not(.i18n_value-replaced)').each(function() {
var element = $(this);
$('[i18n_value]:not(.i18n_value-replaced)').each(function() {
var element = $(this);""
element.val(translate(element.attr('i18n_value')));
element.addClass('i18n_value-replaced');
});
element.val(self.translate(element.attr('i18n_value')));
element.addClass('i18n_value-replaced');
});
$('[i18n_placeholder]:not(.i18n_placeholder-replaced)').each(function() {
var element = $(this);
$('[i18n_placeholder]:not(.i18n_placeholder-replaced)').each(function() {
var element = $(this);
element.attr('placeholder', translate(element.attr('i18n_placeholder')));
element.addClass('i18n_placeholder-replaced');
});
element.attr('placeholder', self.translate(element.attr('i18n_placeholder')));
element.addClass('i18n_placeholder-replaced');
});
return localized;
}
return self;
return localized;
}

629
js/main.js Normal file
View file

@ -0,0 +1,629 @@
window.$ = window.jQuery = require('jquery'),
require('jquery-ui-dist/jquery-ui');
const { SerialPort } = require('serialport');
const path = require('path');
const { app } = require('@electron/remote');
const ol = require('openlayers');
const Store = require('electron-store');
const store = new Store();
var localization;
// Set how the units render on the configurator only
const UnitType = {
none: "none",
OSD: "OSD",
imperial: "imperial",
metric: "metric",
}
let globalSettings = {
// Configurator rendering options
// Used to depict how the units are displayed within the UI
unitType: null,
// Used to convert units within the UI
osdUnits: null,
// Map
mapProviderType: null,
mapApiKey: null,
proxyURL: null,
proxyLayer: null,
// Show colours for profiles
showProfileParameters: null,
// tree target for documents
docsTreeLocation: 'master',
};
$(document).on("ready", () => {
localization = new Localiziation("en");
localization.localize();
globalSettings.unitType = store.get('unit_type', UnitType.none);
globalSettings.mapProviderType = store.get('map_provider_type', 'osm');
globalSettings.mapApiKey = store.get('map_api_key', '');
globalSettings.proxyURL = store.get('proxyurl', 'http://192.168.1.222/mapproxy/service?');
globalSettings.proxyLayer = store.get('proxylayer', 'your_proxy_layer_name');
globalSettings.showProfileParameters = store.get('show_profile_parameters', 1);
updateProfilesHighlightColours();
// Resets the OSD units used by the unit coversion when the FC is disconnected.
if (!CONFIGURATOR.connectionValid) {
globalSettings.osdUnits = null;
}
// alternative - window.navigator.appVersion.match(/Chrome\/([0-9.]*)/)[1];
GUI.log(localization.getMessage('getRunningOS') + GUI.operating_system + '</strong>, ' +
'Chrome: <strong>' + process.versions['chrome'] + '</strong>, ' +
localization.getMessage('getConfiguratorVersion') + app.getVersion() + '</strong>');
$('#status-bar .version').text(app.getVersion());
$('#logo .version').text(app.getVersion());
updateFirmwareVersion();
if (store.get('logopen', false)) {
$("#showlog").trigger('click');
}
if (store.get('update_notify', true)) {
appUpdater.checkRelease(app.getVersion());
}
// log library versions in console to make version tracking easier
console.log('Libraries: jQuery - ' + $.fn.jquery + ', d3 - ' + d3.version + ', three.js - ' + THREE.REVISION);
// Tabs
var ui_tabs = $('#tabs > ul');
$('a', ui_tabs).click(function () {
if ($(this).parent().hasClass("tab_help")) {
return;
}
if ($(this).parent().hasClass('active') == false && !GUI.tab_switch_in_progress) { // only initialize when the tab isn't already active
var self = this,
tabClass = $(self).parent().prop('class');
var tabRequiresConnection = $(self).parent().hasClass('mode-connected');
var tab = tabClass.substring(4);
var tabName = $(self).text();
if (tabRequiresConnection && !CONFIGURATOR.connectionValid) {
GUI.log(localization.getMessage('tabSwitchConnectionRequired'));
return;
}
if (GUI.connect_lock) { // tab switching disabled while operation is in progress
GUI.log(localization.getMessage('tabSwitchWaitForOperation'));
return;
}
if (GUI.allowedTabs.indexOf(tab) < 0) {
GUI.log(localization.getMessage('tabSwitchUpgradeRequired', [tabName]));
return;
}
GUI.tab_switch_in_progress = true;
GUI.tab_switch_cleanup(function () {
// disable previously active tab highlight
$('li', ui_tabs).removeClass('active');
// Highlight selected tab
$(self).parent().addClass('active');
// detach listeners and remove element data
var content = $('#content');
content.data('empty', !!content.is(':empty'));
content.empty();
// display loading screen
$('#cache .data-loading').clone().appendTo(content);
function content_ready() {
GUI.tab_switch_in_progress = false;
// Update CSS on to show highlighing or not
updateProfilesHighlightColours();
}
switch (tab) {
case 'landing':
TABS.landing.initialize(content_ready);
break;
case 'firmware_flasher':
TABS.firmware_flasher.initialize(content_ready);
break;
case 'sitl':
TABS.sitl.initialize(content_ready);
break;
case 'auxiliary':
TABS.auxiliary.initialize(content_ready);
break;
case 'adjustments':
TABS.adjustments.initialize(content_ready);
break;
case 'ports':
TABS.ports.initialize(content_ready);
break;
case 'led_strip':
TABS.led_strip.initialize(content_ready);
break;
case 'failsafe':
TABS.failsafe.initialize(content_ready);
break;
case 'setup':
TABS.setup.initialize(content_ready);
break;
case 'calibration':
TABS.calibration.initialize(content_ready);
break;
case 'configuration':
TABS.configuration.initialize(content_ready);
break;
case 'profiles':
TABS.profiles.initialize(content_ready);
break;
case 'pid_tuning':
TABS.pid_tuning.initialize(content_ready);
break;
case 'receiver':
TABS.receiver.initialize(content_ready);
break;
case 'modes':
TABS.modes.initialize(content_ready);
break;
case 'servos':
TABS.servos.initialize(content_ready);
break;
case 'gps':
TABS.gps.initialize(content_ready);
break;
case 'magnetometer':
TABS.magnetometer.initialize(content_ready);
break;
case 'mission_control':
TABS.mission_control.initialize(content_ready);
break;
case 'mixer':
TABS.mixer.initialize(content_ready);
break;
case 'outputs':
TABS.outputs.initialize(content_ready);
break;
case 'osd':
TABS.osd.initialize(content_ready);
break;
case 'sensors':
TABS.sensors.initialize(content_ready);
break;
case 'logging':
TABS.logging.initialize(content_ready);
break;
case 'onboard_logging':
TABS.onboard_logging.initialize(content_ready);
break;
case 'advanced_tuning':
TABS.advanced_tuning.initialize(content_ready);
break;
case 'programming':
TABS.programming.initialize(content_ready);
break;
case 'cli':
TABS.cli.initialize(content_ready);
break;
case 'ez_tune':
TABS.ez_tune.initialize(content_ready);
break;
default:
console.log('Tab not found:' + tab);
}
});
}
});
$('#tabs ul.mode-disconnected li a:first').click();
// options
$('#options').click(function () {
var el = $(this);
if (!el.hasClass('active')) {
el.addClass('active');
el.after('<div id="options-window"></div>');
$('div#options-window').load('/html//options.html', function () {
// translate to user-selected language
localization.localize();
// if notifications are enabled, or wasn't set, check the notifications checkbox
if (store.get('update_notify', true)) {
$('div.notifications input').prop('checked', true);
}
$('div.notifications input').change(function () {
var check = $(this).is(':checked');
store.set('update_notify', check);
});
$('div.statistics input').change(function () {
var check = $(this).is(':checked');
});
$('div.show_profile_parameters input').change(function () {
globalSettings.showProfileParameters = $(this).is(':checked');
store.set('show_profile_parameters', globalSettings.showProfileParameters);
// Update CSS on select boxes
updateProfilesHighlightColours();
// Horrible way to reload the tab
const activeTab = $('#tabs li.active');
activeTab.removeClass('active');
activeTab.find('a').click();
});
$('#ui-unit-type').val(globalSettings.unitType);
$('#map-provider-type').val(globalSettings.mapProviderType);
$('#map-api-key').val(globalSettings.mapApiKey);
$('#proxyurl').val(globalSettings.proxyURL);
$('#proxylayer').val(globalSettings.proxyLayer);
$('#showProfileParameters').prop('checked', globalSettings.showProfileParameters);
// Set the value of the unit type
// none, OSD, imperial, metric
$('#ui-unit-type').change(function () {
store.set('unit_type', $(this).val());
globalSettings.unitType = $(this).val();
// Update the osd units in global settings
// but only if we need it
if (globalSettings.unitType === UnitType.OSD) {
get_osd_settings();
}
// Horrible way to reload the tab
const activeTab = $('#tabs li.active');
activeTab.removeClass('active');
activeTab.find('a').click();
});
$('#map-provider-type').change(function () {
store.set('map_provider_type', $(this).val());
globalSettings.mapProviderType = $(this).val();
});
$('#map-api-key').change(function () {
store.set('map_api_key', $(this).val());
globalSettings.mapApiKey = $(this).val();
});
$('#proxyurl').change(function () {
store.set('proxyurl', $(this).val());
globalSettings.proxyURL = $(this).val();
});
$('#proxylayer').change(function () {
store.set('proxylayer', $(this).val());
globalSettings.proxyLayer = $(this).val();
});
$('#demoModeReset').on('click', () => {
SITLProcess.deleteEepromFile('demo.bin');
});
function close_and_cleanup(e) {
if (e.type == 'click' && !$.contains($('div#options-window')[0], e.target) || e.type == 'keyup' && e.keyCode == 27) {
$(document).unbind('click keyup', close_and_cleanup);
$('div#options-window').slideUp(250, function () {
el.removeClass('active');
$(this).empty().remove();
});
}
}
$(document).bind('click keyup', close_and_cleanup);
$(this).slideDown(250);
});
}
});
var $content = $("#content");
// listen to all input change events and adjust the value within limits if necessary
$content.on('focus', 'input[type="number"]', function () {
var element = $(this),
val = element.val();
if (!isNaN(val)) {
element.data('previousValue', parseFloat(val));
}
});
$content.on('keydown', 'input[type="number"]', function (e) {
// whitelist all that we need for numeric control
var whitelist = [
96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, // numpad and standard number keypad
109, 189, // minus on numpad and in standard keyboard
8, 46, 9, // backspace, delete, tab
190, 110, // decimal point
37, 38, 39, 40, 13 // arrows and enter
];
if (whitelist.indexOf(e.keyCode) == -1) {
e.preventDefault();
}
});
$content.on('change', 'input[type="number"]', function () {
var element = $(this),
min = parseFloat(element.prop('min')),
max = parseFloat(element.prop('max')),
step = parseFloat(element.prop('step')),
val = parseFloat(element.val()),
decimal_places;
// only adjust minimal end if bound is set
if (element.prop('min')) {
if (val < min) {
element.val(min);
val = min;
}
}
// only adjust maximal end if bound is set
if (element.prop('max')) {
if (val > max) {
element.val(max);
val = max;
}
}
// if entered value is illegal use previous value instead
if (isNaN(val)) {
element.val(element.data('previousValue'));
val = element.data('previousValue');
}
// if step is not set or step is int and value is float use previous value instead
if (isNaN(step) || step % 1 === 0) {
if (val % 1 !== 0) {
element.val(element.data('previousValue'));
val = element.data('previousValue');
}
}
// if step is set and is float and value is int, convert to float, keep decimal places in float according to step *experimental*
if (!isNaN(step) && step % 1 !== 0) {
decimal_places = String(step).split('.')[1].length;
if (val % 1 === 0) {
element.val(val.toFixed(decimal_places));
} else if (String(val).split('.')[1].length != decimal_places) {
element.val(val.toFixed(decimal_places));
}
}
});
$("#showlog").on('click', function() {
var state = $(this).data('state'),
$log = $("#log");
if (state) {
$log.animate({height: 27}, 200, function() {
var command_log = $('div#log');
//noinspection JSValidateTypes
command_log.scrollTop($('div.wrapper', command_log).height());
});
$log.removeClass('active');
$("#content").removeClass('logopen');
$(".tab_container").removeClass('logopen');
$("#scrollicon").removeClass('active');
store.set('logopen', false);
state = false;
}else{
$log.animate({height: 111}, 200);
$log.addClass('active');
$("#content").addClass('logopen');
$(".tab_container").addClass('logopen');
$("#scrollicon").addClass('active');
store.set('logopen', true);
state = true;
}
$(this).html(state ? localization.getMessage("mainHideLog") : localization.getMessage("mainShowLog"));
$(this).data('state', state);
});
var mixerprofile_e = $('#mixerprofilechange');
mixerprofile_e.change(function () {
var mixerprofile = parseInt($(this).val());
MSP.send_message(MSPCodes.MSP2_INAV_SELECT_MIXER_PROFILE, [mixerprofile], false, function () {
GUI.log(localization.getMessage('loadedMixerProfile', [mixerprofile + 1]));
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, function () {
GUI.log(localization.getMessage('deviceRebooting'));
GUI.handleReconnect();
});
});
});
var profile_e = $('#profilechange');
profile_e.change(function () {
var profile = parseInt($(this).val());
MSP.send_message(MSPCodes.MSP_SELECT_SETTING, [profile], false, function () {
GUI.log(localization.getMessage('pidTuning_LoadedProfile', [profile + 1]));
});
});
var batteryprofile_e = $('#batteryprofilechange');
batteryprofile_e.change(function () {
var batteryprofile = parseInt($(this).val());
MSP.send_message(MSPCodes.MSP2_INAV_SELECT_BATTERY_PROFILE, [batteryprofile], false, function () {
GUI.log(localization.getMessage('loadedBatteryProfile', [batteryprofile + 1]));
});
});
});
function get_osd_settings() {
if (globalSettings.osdUnits !== undefined && globalSettings.osdUnits !== null) {
return;
}
MSP.promise(MSPCodes.MSP2_INAV_OSD_PREFERENCES).then(function (resp) {
var prefs = resp.data;
prefs.readU8();
prefs.readU8();
prefs.readU8();
prefs.readU8();
prefs.readU8();
prefs.readU8();
prefs.readU8();
globalSettings.osdUnits = prefs.readU8();
});
}
function updateProfilesHighlightColours() {
if (globalSettings.showProfileParameters) {
$('.dropdown-dark #profilechange').addClass('showProfileParams');
$('.dropdown-dark #batteryprofilechange').addClass('showProfileParams');
$('.batteryProfileHighlight').each(function () {
$(this).addClass('batteryProfileHighlightActive');
$(this).removeClass('batteryProfileHighlight');
});
$('.controlProfileHighlight').each(function () {
$(this).addClass('controlProfileHighlightActive');
$(this).removeClass('controlProfileHighlight');
});
} else {
$('.dropdown-dark #profilechange').removeClass('showProfileParams');
$('.dropdown-dark #batteryprofilechange').removeClass('showProfileParams');
$('.batteryProfileHighlightActive').each(function () {
$(this).addClass('batteryProfileHighlight');
$(this).removeClass('batteryProfileHighlightActive');
});
$('.controlProfileHighlightActive').each(function () {
$(this).addClass('controlProfileHighlight');
$(this).removeClass('controlProfileHighlightActive');
});
}
}
function catch_startup_time(startTime) {
var endTime = new Date().getTime(),
timeSpent = endTime - startTime;
}
function millitime() {
return new Date().getTime();
}
function bytesToSize(bytes) {
if (bytes < 1024) {
bytes = bytes + ' Bytes';
} else if (bytes < 1048576) {
bytes = (bytes / 1024).toFixed(3) + ' KB';
} else if (bytes < 1073741824) {
bytes = (bytes / 1048576).toFixed(3) + ' MB';
} else {
bytes = (bytes / 1073741824).toFixed(3) + ' GB';
}
return bytes;
}
Number.prototype.clamp = function (min, max) {
return Math.min(Math.max(this, min), max);
};
/**
* String formatting now supports currying (partial application).
* For a format string with N replacement indices, you can call .format
* with M <= N arguments. The result is going to be a format string
* with N-M replacement indices, properly counting from 0 .. N-M.
* The following Example should explain the usage of partial applied format:
* "{0}:{1}:{2}".format("a","b","c") === "{0}:{1}:{2}".format("a","b").format("c")
* "{0}:{1}:{2}".format("a").format("b").format("c") === "{0}:{1}:{2}".format("a").format("b", "c")
**/
String.prototype.format = function () {
var args = arguments;
return this.replace(/\{(\d+)\}/g, function (t, i) {
return args[i] !== void 0 ? args[i] : "{" + (i - args.length) + "}";
});
};
function padZeros(val, length) {
let str = val.toString();
if (str.length < length) {
if (str.charAt(0) === '-') {
str = "-0" + str.substring(1);
str = padZeros(str, length);
} else {
str = padZeros("0" + str, length);
}
}
return str;
}
function updateActivatedTab() {
var activeTab = $('#tabs > ul li.active');
activeTab.removeClass('active');
$('a', activeTab).trigger('click');
}
function updateFirmwareVersion() {
if (CONFIGURATOR.connectionValid) {
$('#logo .firmware_version').text(CONFIG.flightControllerVersion + " [" + CONFIG.target + "]");
globalSettings.docsTreeLocation = 'https://github.com/iNavFlight/inav/blob/' + CONFIG.flightControllerVersion + '/docs/';
// If this is a master branch firmware, this will find a 404 as there is no tag tree. So default to master for docs.
$.ajax({
url: globalSettings.docsTreeLocation + 'Settings.md',
method: "HEAD",
statusCode: {
404: function () {
globalSettings.docsTreeLocation = 'https://github.com/iNavFlight/inav/blob/master/docs/';
}
}
});
} else {
$('#logo .firmware_version').text(localization.getMessage('fcNotConnected'));
globalSettings.docsTreeLocation = 'https://github.com/iNavFlight/inav/blob/master/docs/';
}
}
function updateEzTuneTabVisibility(loadMixerConfig) {
let useEzTune = true;
if (CONFIGURATOR.connectionValid) {
if (loadMixerConfig) {
mspHelper.loadMixerConfig(function () {
if (MIXER_CONFIG.platformType == PLATFORM_MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM_TRICOPTER) {
$('.tab_ez_tune').removeClass("is-hidden");
} else {
$('.tab_ez_tune').addClass("is-hidden");
useEzTune = false;
}
});
} else {
if (MIXER_CONFIG.platformType == PLATFORM_MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM_TRICOPTER) {
$('.tab_ez_tune').removeClass("is-hidden");
} else {
$('.tab_ez_tune').addClass("is-hidden");
useEzTune = false;
}
}
}
return useEzTune;
}

View file

@ -31,12 +31,12 @@ const INPUT_STABILIZED_ROLL = 0,
INPUT_RC_AUX4 = 11,
INPUT_GIMBAL_PITCH = 12,
INPUT_GIMBAL_ROLL = 13,
INPUT_FEATURE_FLAPS = 14;
STABILIZED_ROLL_POSITIVE = 23;
STABILIZED_ROLL_NEGATIVE = 24;
STABILIZED_PITCH_POSITIVE = 25;
STABILIZED_PITCH_NEGATIVE = 26;
STABILIZED_YAW_POSITIVE = 27;
INPUT_FEATURE_FLAPS = 14,
STABILIZED_ROLL_POSITIVE = 23,
STABILIZED_ROLL_NEGATIVE = 24,
STABILIZED_PITCH_POSITIVE = 25,
STABILIZED_PITCH_NEGATIVE = 26,
STABILIZED_YAW_POSITIVE = 27,
STABILIZED_YAW_NEGATIVE = 28;
const

View file

@ -298,7 +298,7 @@ var MSP = {
view[4] = code;
checksum = view[3] ^ view[4];
for (ii = 0; ii < payloadLength; ii++) {
for (let ii = 0; ii < payloadLength; ii++) {
view[ii + 5] = data[ii];
checksum ^= data[ii];
}
@ -316,11 +316,11 @@ var MSP = {
view[5] = (code & 0xFF00) >> 8; // code upper byte
view[6] = payloadLength & 0xFF; // payloadLength lower byte
view[7] = (payloadLength & 0xFF00) >> 8; // payloadLength upper byte
for (ii = 0; ii < payloadLength; ii++) {
for (let ii = 0; ii < payloadLength; ii++) {
view[8+ii] = data[ii];
}
checksum = 0;
for (ii = 3; ii < length-1; ii++) {
for (let ii = 3; ii < length-1; ii++) {
checksum = this._crc8_dvb_s2(checksum, view[ii]);
}
view[length-1] = checksum;

View file

@ -245,7 +245,5 @@ var MSPCodes = {
MSP2_INAV_EZ_TUNE: 0x2070,
MSP2_INAV_EZ_TUNE_SET: 0x2071,
MSP2_INAV_SELECT_MIXER_PROFILE: 0x2080,
MSP2_ADSB_VEHICLE_LIST: 0x2090,
MSP2_INAV_SELECT_MIXER_PROFILE: 0x2080
};

View file

@ -1,6 +1,8 @@
/*global $, SERVO_DATA, PID_names, ADJUSTMENT_RANGES, RXFAIL_CONFIG, SERVO_CONFIG,CONFIG*/
'use strict';
const mapSeries = require('promise-map-series')
var mspHelper = (function (gui) {
var self = {};
@ -79,7 +81,7 @@ var mspHelper = (function (gui) {
CONFIG.cpuload = data.getUint16(offset, true);
offset += 2;
profile_byte = data.getUint8(offset++)
let profile_byte = data.getUint8(offset++)
let profile = profile_byte & 0x0F;
profile_changed |= (profile !== CONFIG.profile) && (CONFIG.profile !==-1);
CONFIG.profile = profile;
@ -106,7 +108,7 @@ var mspHelper = (function (gui) {
var words = dataHandler.message_length_expected / 4;
CONFIG.mode = [];
for (i = 0; i < words; ++i)
for (let i = 0; i < words; ++i)
CONFIG.mode.push(data.getUint32(i * 4, true));
break;
@ -142,7 +144,7 @@ var mspHelper = (function (gui) {
break;
case MSPCodes.MSP_SERVO:
var servoCount = dataHandler.message_length_expected / 2;
for (i = 0; i < servoCount; i++) {
for (let i = 0; i < servoCount; i++) {
SERVO_DATA[i] = data.getUint16(needle, true);
needle += 2;
@ -150,7 +152,7 @@ var mspHelper = (function (gui) {
break;
case MSPCodes.MSP_MOTOR:
var motorCount = dataHandler.message_length_expected / 2;
for (i = 0; i < motorCount; i++) {
for (let i = 0; i < motorCount; i++) {
MOTOR_DATA[i] = data.getUint16(needle, true);
needle += 2;
@ -159,7 +161,7 @@ var mspHelper = (function (gui) {
case MSPCodes.MSP_RC:
RC.active_channels = dataHandler.message_length_expected / 2;
for (i = 0; i < RC.active_channels; i++) {
for (let i = 0; i < RC.active_channels; i++) {
RC.channels[i] = data.getUint16((i * 2), true);
}
break;
@ -187,35 +189,6 @@ var mspHelper = (function (gui) {
GPS_DATA.eph = data.getUint16(16, true);
GPS_DATA.epv = data.getUint16(18, true);
break;
case MSPCodes.MSP2_ADSB_VEHICLE_LIST:
var byteOffsetCounter = 0;
ADSB_VEHICLES.vehicles = [];
ADSB_VEHICLES.vehiclesCount = data.getUint8(byteOffsetCounter++);
ADSB_VEHICLES.callsignLength = data.getUint8(byteOffsetCounter++);
for(i = 0; i < ADSB_VEHICLES.vehiclesCount; i++){
var vehicle = {callSignByteArray: [], callsign: "", icao: 0, lat: 0, lon: 0, alt: 0, heading: 0, ttl: 0, tslc: 0, emitterType: 0};
for(ii = 0; ii < ADSB_VEHICLES.callsignLength; ii++){
vehicle.callSignByteArray.push(data.getUint8(byteOffsetCounter++));
}
vehicle.callsign = (String.fromCharCode(...vehicle.callSignByteArray)).replace(/[^\x20-\x7E]/g, '');
vehicle.icao = data.getUint32(byteOffsetCounter, true); byteOffsetCounter += 4;
vehicle.lat = data.getInt32(byteOffsetCounter, true); byteOffsetCounter += 4;
vehicle.lon = data.getInt32(byteOffsetCounter, true); byteOffsetCounter += 4;
vehicle.altCM = data.getInt32(byteOffsetCounter, true); byteOffsetCounter += 4;
vehicle.headingDegrees = data.getUint16(byteOffsetCounter, true); byteOffsetCounter += 2;
vehicle.tslc = data.getUint8(byteOffsetCounter++);
vehicle.emitterType = data.getUint8(byteOffsetCounter++);
vehicle.ttl = data.getUint8(byteOffsetCounter++);
ADSB_VEHICLES.vehicles.push(vehicle);
}
break;
case MSPCodes.MSP_ATTITUDE:
SENSOR_DATA.kinematics[0] = data.getInt16(0, true) / 10.0; // x
SENSOR_DATA.kinematics[1] = data.getInt16(2, true) / 10.0; // y
@ -304,7 +277,7 @@ var mspHelper = (function (gui) {
break;
case MSPCodes.MSP2_PID:
// PID data arrived, we need to scale it and save to appropriate bank / array
for (i = 0, needle = 0; i < (dataHandler.message_length_expected / 4); i++, needle += 4) {
for (let i = 0, needle = 0; i < (dataHandler.message_length_expected / 4); i++, needle += 4) {
PIDs[i][0] = data.getUint8(needle);
PIDs[i][1] = data.getUint8(needle + 1);
PIDs[i][2] = data.getUint8(needle + 2);
@ -421,7 +394,7 @@ var mspHelper = (function (gui) {
//noinspection JSUndeclaredVariable
AUX_CONFIG = []; // empty the array as new data is coming in
buff = [];
for (i = 0; i < data.byteLength; i++) {
for (let i = 0; i < data.byteLength; i++) {
if (data.getUint8(i) == 0x3B) { // ; (delimeter char)
AUX_CONFIG.push(String.fromCharCode.apply(null, buff)); // convert bytes into ASCII and save as strings
@ -437,7 +410,7 @@ var mspHelper = (function (gui) {
PID_names = []; // empty the array as new data is coming in
buff = [];
for (i = 0; i < data.byteLength; i++) {
for (let i = 0; i < data.byteLength; i++) {
if (data.getUint8(i) == 0x3B) { // ; (delimiter char)
PID_names.push(String.fromCharCode.apply(null, buff)); // convert bytes into ASCII and save as strings
@ -465,14 +438,14 @@ var mspHelper = (function (gui) {
//noinspection JSUndeclaredVariable
AUX_CONFIG_IDS = []; // empty the array as new data is coming in
for (i = 0; i < data.byteLength; i++) {
for (let i = 0; i < data.byteLength; i++) {
AUX_CONFIG_IDS.push(data.getUint8(i));
}
break;
case MSPCodes.MSP_SERVO_MIX_RULES:
SERVO_RULES.flush();
if (data.byteLength % 8 === 0) {
for (i = 0; i < data.byteLength; i += 8) {
for (let i = 0; i < data.byteLength; i += 8) {
SERVO_RULES.put(new ServoMixRule(
data.getInt8(i),
data.getInt8(i + 1),
@ -487,7 +460,7 @@ var mspHelper = (function (gui) {
case MSPCodes.MSP2_INAV_SERVO_MIXER:
SERVO_RULES.flush();
if (data.byteLength % 6 === 0) {
for (i = 0; i < data.byteLength; i += 6) {
for (let i = 0; i < data.byteLength; i += 6) {
SERVO_RULES.put(new ServoMixRule(
data.getInt8(i),
data.getInt8(i + 1),
@ -509,7 +482,7 @@ var mspHelper = (function (gui) {
case MSPCodes.MSP2_INAV_LOGIC_CONDITIONS:
LOGIC_CONDITIONS.flush();
if (data.byteLength % 14 === 0) {
for (i = 0; i < data.byteLength; i += 14) {
for (let i = 0; i < data.byteLength; i += 14) {
LOGIC_CONDITIONS.put(new LogicCondition(
data.getInt8(i),
data.getInt8(i + 1),
@ -540,7 +513,7 @@ var mspHelper = (function (gui) {
case MSPCodes.MSP2_INAV_LOGIC_CONDITIONS_STATUS:
if (data.byteLength % 4 === 0) {
let index = 0;
for (i = 0; i < data.byteLength; i += 4) {
for (let i = 0; i < data.byteLength; i += 4) {
LOGIC_CONDITIONS_STATUS.set(index, data.getInt32(i, true));
index++;
}
@ -550,7 +523,7 @@ var mspHelper = (function (gui) {
case MSPCodes.MSP2_INAV_GVAR_STATUS:
if (data.byteLength % 4 === 0) {
let index = 0;
for (i = 0; i < data.byteLength; i += 4) {
for (let i = 0; i < data.byteLength; i += 4) {
GLOBAL_VARIABLES_STATUS.set(index, data.getInt32(i, true));
index++;
}
@ -564,7 +537,7 @@ var mspHelper = (function (gui) {
case MSPCodes.MSP2_INAV_PROGRAMMING_PID:
PROGRAMMING_PID.flush();
if (data.byteLength % 19 === 0) {
for (i = 0; i < data.byteLength; i += 19) {
for (let i = 0; i < data.byteLength; i += 19) {
PROGRAMMING_PID.put(new ProgrammingPid(
data.getInt8(i), // enabled
data.getInt8(i + 1), // setpointType
@ -583,7 +556,7 @@ var mspHelper = (function (gui) {
case MSPCodes.MSP2_INAV_PROGRAMMING_PID_STATUS:
if (data.byteLength % 4 === 0) {
let index = 0;
for (i = 0; i < data.byteLength; i += 4) {
for (let i = 0; i < data.byteLength; i += 4) {
PROGRAMMING_PID_STATUS.set(index, data.getInt32(i, true));
index++;
}
@ -598,7 +571,7 @@ var mspHelper = (function (gui) {
MOTOR_RULES.flush();
if (data.byteLength % 8 === 0) {
for (i = 0; i < data.byteLength; i += 8) {
for (let i = 0; i < data.byteLength; i += 8) {
var rule = new MotorMixRule(0, 0, 0, 0);
rule.fromMsp(
@ -624,7 +597,7 @@ var mspHelper = (function (gui) {
SERVO_CONFIG = []; // empty the array as new data is coming in
if (data.byteLength % 14 == 0) {
for (i = 0; i < data.byteLength; i += 14) {
for (let i = 0; i < data.byteLength; i += 14) {
var arr = {
'min': data.getInt16(i + 0, true),
'max': data.getInt16(i + 2, true),
@ -709,11 +682,11 @@ var mspHelper = (function (gui) {
}
break;
case MSPCodes.MSP_DEBUG:
for (i = 0; i < 4; i++)
for (let i = 0; i < 4; i++)
SENSOR_DATA.debug[i] = data.getInt16((2 * i), 1);
break;
case MSPCodes.MSP2_INAV_DEBUG:
for (i = 0; i < 8; i++)
for (let i = 0; i < 8; i++)
SENSOR_DATA.debug[i] = data.getInt32((4 * i), 1);
break;
case MSPCodes.MSP_SET_MOTOR:
@ -737,7 +710,7 @@ var mspHelper = (function (gui) {
//noinspection JSUndeclaredVariable
RC_MAP = []; // empty the array as new data is coming in
for (i = 0; i < data.byteLength; i++) {
for (let i = 0; i < data.byteLength; i++) {
RC_MAP.push(data.getUint8(i));
}
break;
@ -802,13 +775,13 @@ var mspHelper = (function (gui) {
var dateLength = 11;
buff = [];
for (i = 0; i < dateLength; i++) {
for (let i = 0; i < dateLength; i++) {
buff.push(data.getUint8(offset++));
}
buff.push(32); // ascii space
var timeLength = 8;
for (i = 0; i < timeLength; i++) {
for (let i = 0; i < timeLength; i++) {
buff.push(data.getUint8(offset++));
}
CONFIG.buildInfo = String.fromCharCode.apply(null, buff);
@ -844,7 +817,7 @@ var mspHelper = (function (gui) {
var bytesPerPort = 1 + 4 + 4;
var serialPortCount = data.byteLength / bytesPerPort;
for (i = 0; i < serialPortCount; i++) {
for (let i = 0; i < serialPortCount; i++) {
var BAUD_RATES = mspHelper.BAUD_RATES_post1_6_3;
var serialPort = {
@ -871,7 +844,7 @@ var mspHelper = (function (gui) {
var modeRangeCount = data.byteLength / 4; // 4 bytes per item.
for (i = 0; offset < data.byteLength && i < modeRangeCount; i++) {
for (let i = 0; offset < data.byteLength && i < modeRangeCount; i++) {
var modeRange = {
id: data.getUint8(offset++),
auxChannelIndex: data.getUint8(offset++),
@ -890,7 +863,7 @@ var mspHelper = (function (gui) {
var adjustmentRangeCount = data.byteLength / 6; // 6 bytes per item.
for (i = 0; offset < data.byteLength && i < adjustmentRangeCount; i++) {
for (let i = 0; offset < data.byteLength && i < adjustmentRangeCount; i++) {
var adjustmentRange = {
slotIndex: data.getUint8(offset++),
auxChannelIndex: data.getUint8(offset++),
@ -906,7 +879,7 @@ var mspHelper = (function (gui) {
break;
case MSPCodes.MSP_CHANNEL_FORWARDING:
for (i = 0; i < data.byteLength && i < SERVO_CONFIG.length; i++) {
for (let i = 0; i < data.byteLength && i < SERVO_CONFIG.length; i++) {
var channelIndex = data.getUint8(i);
if (channelIndex < 255) {
SERVO_CONFIG[i].indexOfChannelToForward = channelIndex;
@ -979,7 +952,7 @@ var mspHelper = (function (gui) {
var channelCount = data.byteLength / 3;
for (i = 0; offset < data.byteLength && i < channelCount; i++, offset++) {
for (let i = 0; offset < data.byteLength && i < channelCount; i++, offset++) {
var rxfailChannel = {
mode: data.getUint8(offset++),
value: data.getUint16(offset++, true)
@ -1000,7 +973,7 @@ var mspHelper = (function (gui) {
functions,
led;
for (i = 0; offset < data.byteLength && i < ledCount; i++) {
for (let i = 0; offset < data.byteLength && i < ledCount; i++) {
if (semver.lt(CONFIG.apiVersion, "1.20.0")) {
directionMask = data.getUint16(offset, true);
@ -1085,7 +1058,7 @@ var mspHelper = (function (gui) {
functions,
led;
for (i = 0; offset < data.byteLength && i < ledCount; i++) {
for (let i = 0; offset < data.byteLength && i < ledCount; i++) {
var mask = data.getUint32(offset, 1);
offset += 4;
var extra = data.getUint8(offset, 1);
@ -1141,7 +1114,7 @@ var mspHelper = (function (gui) {
colorCount = data.byteLength / 4;
for (i = 0; offset < data.byteLength && i < colorCount; i++) {
for (let i = 0; offset < data.byteLength && i < colorCount; i++) {
var h = data.getUint16(offset, true);
var s = data.getUint8(offset + 2);
@ -1167,7 +1140,7 @@ var mspHelper = (function (gui) {
colorCount = data.byteLength / 3;
for (i = 0; offset < data.byteLength && i < colorCount; i++) {
for (let i = 0; offset < data.byteLength && i < colorCount; i++) {
var mode = data.getUint8(offset++);
var direction = data.getUint8(offset++);
@ -1531,16 +1504,16 @@ var mspHelper = (function (gui) {
break;
case MSPCodes.MSPV2_INAV_OUTPUT_MAPPING:
OUTPUT_MAPPING.flush();
for (i = 0; i < data.byteLength; ++i)
for (let i = 0; i < data.byteLength; ++i)
OUTPUT_MAPPING.put({
'timerId': i,
'usageFlags': data.getUint8(i)});
break;
case MSPCodes.MSPV2_INAV_OUTPUT_MAPPING_EXT:
OUTPUT_MAPPING.flush();
for (i = 0; i < data.byteLength; i += 2) {
timerId = data.getUint8(i);
usageFlags = data.getUint8(i + 1);
for (let i = 0; i < data.byteLength; i += 2) {
let timerId = data.getUint8(i);
let usageFlags = data.getUint8(i + 1);
OUTPUT_MAPPING.put(
{
'timerId': timerId,
@ -1553,9 +1526,9 @@ var mspHelper = (function (gui) {
if(data.byteLength > 2) {
OUTPUT_MAPPING.flushTimerOverrides();
}
for (i = 0; i < data.byteLength; i += 2) {
timerId = data.getUint8(i);
outputMode = data.getUint8(i + 1);
for (let i = 0; i < data.byteLength; i += 2) {
let timerId = data.getUint8(i);
let outputMode = data.getUint8(i + 1);
OUTPUT_MAPPING.setTimerOverride(timerId, outputMode);
}
break;
@ -1590,7 +1563,7 @@ var mspHelper = (function (gui) {
break;
case MSPCodes.MSP2_INAV_TEMPERATURES:
for (i = 0; i < 8; ++i) {
for (let i = 0; i < 8; ++i) {
temp_decidegrees = data.getInt16(i * 2, true);
SENSOR_DATA.temperature[i] = temp_decidegrees / 10; // °C
}
@ -1643,7 +1616,7 @@ var mspHelper = (function (gui) {
}
// trigger callbacks, cleanup/remove callback after trigger
for (i = dataHandler.callbacks.length - 1; i >= 0; i--) { // iterating in reverse because we use .splice which modifies array length
for (let i = dataHandler.callbacks.length - 1; i >= 0; i--) { // iterating in reverse because we use .splice which modifies array length
if (i < dataHandler.callbacks.length) {
if (dataHandler.callbacks[i].code == dataHandler.code) {
// save callback reference
@ -1718,7 +1691,7 @@ var mspHelper = (function (gui) {
buffer.push(VTX_CONFIG.low_power_disarm);
break;
case MSPCodes.MSP2_SET_PID:
for (i = 0; i < PIDs.length; i++) {
for (let i = 0; i < PIDs.length; i++) {
buffer.push(parseInt(PIDs[i][0]));
buffer.push(parseInt(PIDs[i][1]));
buffer.push(parseInt(PIDs[i][2]));
@ -1762,7 +1735,7 @@ var mspHelper = (function (gui) {
break;
case MSPCodes.MSP_SET_RX_MAP:
for (i = 0; i < RC_MAP.length; i++) {
for (let i = 0; i < RC_MAP.length; i++) {
buffer.push(RC_MAP[i]);
}
break;
@ -1833,11 +1806,11 @@ var mspHelper = (function (gui) {
buffer.push(highByte(Math.round(MISC.vbatmaxcellvoltage * 100)));
buffer.push(lowByte(Math.round(MISC.vbatwarningcellvoltage * 100)));
buffer.push(highByte(Math.round(MISC.vbatwarningcellvoltage * 100)));
for (byte_index = 0; byte_index < 4; ++byte_index)
for (let byte_index = 0; byte_index < 4; ++byte_index)
buffer.push(specificByte(MISC.battery_capacity, byte_index));
for (byte_index = 0; byte_index < 4; ++byte_index)
for (let byte_index = 0; byte_index < 4; ++byte_index)
buffer.push(specificByte(MISC.battery_capacity_warning, byte_index));
for (byte_index = 0; byte_index < 4; ++byte_index)
for (let byte_index = 0; byte_index < 4; ++byte_index)
buffer.push(specificByte(MISC.battery_capacity_critical, byte_index));
buffer.push((MISC.battery_capacity_unit == 'mAh') ? 0 : 1);
break;
@ -1858,11 +1831,11 @@ var mspHelper = (function (gui) {
buffer.push(highByte(BATTERY_CONFIG.current_offset));
buffer.push(lowByte(BATTERY_CONFIG.current_scale));
buffer.push(highByte(BATTERY_CONFIG.current_scale));
for (byte_index = 0; byte_index < 4; ++byte_index)
for (let byte_index = 0; byte_index < 4; ++byte_index)
buffer.push(specificByte(BATTERY_CONFIG.capacity, byte_index));
for (byte_index = 0; byte_index < 4; ++byte_index)
for (let byte_index = 0; byte_index < 4; ++byte_index)
buffer.push(specificByte(BATTERY_CONFIG.capacity_warning, byte_index));
for (byte_index = 0; byte_index < 4; ++byte_index)
for (let byte_index = 0; byte_index < 4; ++byte_index)
buffer.push(specificByte(BATTERY_CONFIG.capacity_critical, byte_index));
buffer.push(BATTERY_CONFIG.capacity_unit);
break;
@ -1918,7 +1891,7 @@ var mspHelper = (function (gui) {
break;
case MSPCodes.MSP_SET_CHANNEL_FORWARDING:
for (i = 0; i < SERVO_CONFIG.length; i++) {
for (let i = 0; i < SERVO_CONFIG.length; i++) {
var out = SERVO_CONFIG[i].indexOfChannelToForward;
if (out == undefined) {
out = 255; // Cleanflight defines "CHANNEL_FORWARDING_DISABLED" as "(uint8_t)0xFF"
@ -1928,7 +1901,7 @@ var mspHelper = (function (gui) {
break;
case MSPCodes.MSP2_SET_CF_SERIAL_CONFIG:
for (i = 0; i < SERIAL_CONFIG.ports.length; i++) {
for (let i = 0; i < SERIAL_CONFIG.ports.length; i++) {
var serialPort = SERIAL_CONFIG.ports[i];
buffer.push(serialPort.identifier);
@ -3173,7 +3146,7 @@ var mspHelper = (function (gui) {
if (waypointId < MISSION_PLANNER.getCountBusyPoints()) {
MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, loadWaypoint);
} else {
GUI.log(chrome.i18n.getMessage('ReceiveTime') + (new Date().getTime() - startTime) + 'ms');
GUI.log(localization.getMessage('ReceiveTime') + (new Date().getTime() - startTime) + 'ms');
MSP.send_message(MSPCodes.MSP_WP, [waypointId], false, callback);
}
};
@ -3195,7 +3168,7 @@ var mspHelper = (function (gui) {
};
function endMission() {
GUI.log(chrome.i18n.getMessage('SendTime') + (new Date().getTime() - startTime) + 'ms');
GUI.log(localization.getMessage('SendTime') + (new Date().getTime() - startTime) + 'ms');
MSP.send_message(MSPCodes.MSP_WP_GETINFO, false, false, callback);
}
};

View file

@ -35,19 +35,19 @@ helper.periodicStatusUpdater = (function () {
if (FC.isModeEnabled('ARM'))
$(".armedicon").css({
'background-image': 'url("../images/icons/cf_icon_armed_active.svg")'
'background-image': 'url("./images/icons/cf_icon_armed_active.svg")'
});
else
$(".armedicon").css({
'background-image': 'url("../images/icons/cf_icon_armed_grey.svg")'
'background-image': 'url("./images/icons/cf_icon_armed_grey.svg")'
});
if (FC.isModeEnabled('FAILSAFE'))
$(".failsafeicon").css({
'background-image': 'url("../images/icons/cf_icon_failsafe_active.svg")'
'background-image': 'url("./images/icons/cf_icon_failsafe_active.svg")'
});
else
$(".failsafeicon").css({
'background-image': 'url("../images/icons/cf_icon_failsafe_grey.svg")'
'background-image': 'url("./images/icons/cf_icon_failsafe_grey.svg")'
});
if (ANALOG != undefined) {
@ -65,11 +65,11 @@ helper.periodicStatusUpdater = (function () {
if (active) {
$(".linkicon").css({
'background-image': 'url("../images/icons/cf_icon_link_active.svg")'
'background-image': 'url("./images/icons/cf_icon_link_active.svg")'
});
} else {
$(".linkicon").css({
'background-image': 'url("../images/icons/cf_icon_link_grey.svg")'
'background-image': 'url("./images/icons/cf_icon_link_grey.svg")'
});
}

View file

@ -1,11 +1,13 @@
'use strict';
var usbDevices = {
filters: [
{'vendorId': 1155, 'productId': 57105},
{'vendorId': 11836, 'productId': 57105}
]
};
const { findByIds } = require('usb');
var usbDevices = [
{ 'vendorId': 1155, 'productId': 57105},
{ 'vendorId': 11836, 'productId': 57105}
];
// TODO: Replace with events
var PortHandler = new function () {
this.initial_ports = false;
@ -22,16 +24,7 @@ PortHandler.initialize = function () {
PortHandler.check = function () {
var self = this;
ConnectionSerial.getDevices(function(all_ports) {
// filter out ports that are not serial
let current_ports = [];
for (var i = 0; i < all_ports.length; i++) {
if (all_ports[i].indexOf(':') === -1) {
current_ports.push(all_ports[i]);
}
}
ConnectionSerial.getDevices(function(current_ports) {
// port got removed or initial_ports wasn't initialized yet
if (self.array_difference(self.initial_ports, current_ports).length > 0 || !self.initial_ports) {
var removed_ports = self.array_difference(self.initial_ports, current_ports);
@ -75,35 +68,31 @@ PortHandler.check = function () {
// auto-select last used port (only during initialization)
if (!self.initial_ports) {
chrome.storage.local.get('last_used_port', function (result) {
// if last_used_port was set, we try to select it
if (result.last_used_port) {
if (result.last_used_port == "ble" || result.last_used_port == "tcp" || result.last_used_port == "udp" || result.last_used_port == "sitl" || result.last_used_port == "sitl-demo") {
$('#port').val(result.last_used_port);
} else {
current_ports.forEach(function(port) {
if (port == result.last_used_port) {
console.log('Selecting last used port: ' + result.last_used_port);
$('#port').val(result.last_used_port);
}
});
}
var last_used_port = store.get('last_used_port', false);
// if last_used_port was set, we try to select it
if (last_used_port) {
if (last_used_port == "ble" || last_used_port == "tcp" || last_used_port == "udp" || last_used_port == "sitl" || last_used_port == "sitl-demo") {
$('#port').val(last_used_port);
} else {
console.log('Last used port wasn\'t saved "yet", auto-select disabled.');
current_ports.forEach(function(port) {
if (port == last_used_port) {
console.log('Selecting last used port: ' + last_used_port);
$('#port').val(last_used_port);
}
});
}
});
} else {
console.log('Last used port wasn\'t saved "yet", auto-select disabled.');
}
var last_used_bps = store.get('last_used_bps', false);
if (last_used_bps) {
$('#baud').val(last_used_bps);
}
chrome.storage.local.get('last_used_bps', function (result) {
if (result['last_used_bps']) {
$('#baud').val(result['last_used_bps']);
}
});
chrome.storage.local.get('wireless_mode_enabled', function (result) {
if (result['wireless_mode_enabled']) {
$('#wireless-mode').prop('checked', true).change();
}
});
if (store.get('wireless_mode_enabled', false)) {
$('#wireless-mode').prop('checked', true).change();
}
}
@ -154,7 +143,7 @@ PortHandler.check = function () {
self.initial_ports = current_ports;
}
self.check_usb_devices();
//self.check_usb_devices();
GUI.updateManualPortVisibility();
setTimeout(function () {
@ -164,22 +153,29 @@ PortHandler.check = function () {
};
PortHandler.check_usb_devices = function (callback) {
chrome.usb.getDevices(usbDevices, function (result) {
if (result.length) {
if (!$("div#port-picker #port [value='DFU']").length) {
$('div#port-picker #port').append($('<option/>', {value: "DFU", text: "DFU", data: {isDFU: true}}));
$('div#port-picker #port').val('DFU');
}
self.dfu_available = false;
for (const device of usbDevices) {
if (findByIds(device.vendorId, device.productId)) {
self.dfu_available = true;
} else {
if ($("div#port-picker #port [value='DFU']").length) {
$("div#port-picker #port [value='DFU']").remove();
}
self.dfu_available = false;
break;
}
}
if (self.dfu_available) {
if (!$("div#port-picker #port [value='DFU']").length) {
$('div#port-picker #port').append($('<option/>', {value: "DFU", text: "DFU", data: {isDFU: true}}));
$('div#port-picker #port').val('DFU');
}
} else {
if ($("div#port-picker #port [value='DFU']").length) {
$("div#port-picker #port [value='DFU']").remove();
}
}
if (callback)
callback(self.dfu_available);
if (callback) callback(self.dfu_available);
});
};
PortHandler.update_port_select = function (ports) {

View file

@ -81,7 +81,7 @@ STM32_protocol.prototype.connect = function (port, baud, hex, options, callback)
self.initialize();
} else {
GUI.log(chrome.i18n.getMessage('failedToOpenSerialPort'));
GUI.log(localization.getMessage('failedToOpenSerialPort'));
}
});
} else {
@ -108,7 +108,7 @@ STM32_protocol.prototype.connect = function (port, baud, hex, options, callback)
retries++;
if (retries > maxRetries) {
clearInterval(interval);
GUI.log(chrome.i18n.getMessage('failedToFlash') + port);
GUI.log(localization.getMessage('failedToFlash') + port);
}
}
// Check for DFU devices
@ -145,7 +145,7 @@ STM32_protocol.prototype.connect = function (port, baud, hex, options, callback)
});
});
} else {
GUI.log(chrome.i18n.getMessage('failedToOpenSerialPort'));
GUI.log(localization.getMessage('failedToOpenSerialPort'));
}
});
}
@ -183,7 +183,6 @@ STM32_protocol.prototype.initialize = function () {
$('span.progressLabel').text('STM32 - timed out, programming: FAILED');
self.progress_bar_e.addClass('invalid');
googleAnalytics.sendEvent('Flashing', 'Programming', 'timeout');
// protocol got stuck, clear timer and disconnect
helper.interval.remove('STM32_timeout');
@ -722,7 +721,6 @@ STM32_protocol.prototype.upload_procedure = function (step) {
if (verify) {
console.log('Programming: SUCCESSFUL');
$('span.progressLabel').text('Programming: SUCCESSFUL');
googleAnalytics.sendEvent('Flashing', 'Programming', 'success');
// update progress bar
self.progress_bar_e.addClass('valid');
@ -732,7 +730,6 @@ STM32_protocol.prototype.upload_procedure = function (step) {
} else {
console.log('Programming: FAILED');
$('span.progressLabel').text('Programming: FAILED');
googleAnalytics.sendEvent('Flashing', 'Programming', 'fail');
// update progress bar
self.progress_bar_e.addClass('invalid');

View file

@ -97,7 +97,7 @@ STM32DFU_protocol.prototype.connect = function (device, hex, options, callback)
self.openDevice(result[0]);
} else {
console.log('USB DFU not found');
GUI.log(chrome.i18n.getMessage('stm32UsbDfuNotFound'));
GUI.log(localization.getMessage('stm32UsbDfuNotFound'));
}
});
};
@ -108,16 +108,16 @@ STM32DFU_protocol.prototype.openDevice = function (device) {
chrome.usb.openDevice(device, function (handle) {
if (checkChromeRuntimeError()) {
console.log('Failed to open USB device!');
GUI.log(chrome.i18n.getMessage('usbDeviceOpenFail'));
GUI.log(localization.getMessage('usbDeviceOpenFail'));
if(GUI.operating_system === 'Linux') {
GUI.log(chrome.i18n.getMessage('usbDeviceUdevNotice'));
GUI.log(localization.getMessage('usbDeviceUdevNotice'));
}
return;
}
self.handle = handle;
GUI.log(chrome.i18n.getMessage('usbDeviceOpened', handle.handle.toString()));
GUI.log(localization.getMessage('usbDeviceOpened', handle.handle.toString()));
console.log('Device opened with Handle ID: ' + handle.handle);
self.claimInterface(0);
});
@ -129,10 +129,10 @@ STM32DFU_protocol.prototype.closeDevice = function () {
chrome.usb.closeDevice(this.handle, function closed() {
if (checkChromeRuntimeError()) {
console.log('Failed to close USB device!');
GUI.log(chrome.i18n.getMessage('usbDeviceCloseFail'));
GUI.log(localization.getMessage('usbDeviceCloseFail'));
}
GUI.log(chrome.i18n.getMessage('usbDeviceClosed'));
GUI.log(localization.getMessage('usbDeviceClosed'));
console.log('Device closed with Handle ID: ' + self.handle.handle);
self.handle = null;
@ -568,10 +568,10 @@ STM32DFU_protocol.prototype.upload_procedure = function (step) {
self.flash_layout = chipInfo.internal_flash;
self.available_flash_size = self.flash_layout.total_size - (self.hex.start_linear_address - self.flash_layout.start_address);
GUI.log(chrome.i18n.getMessage('dfu_device_flash_info', (self.flash_layout.total_size / 1024).toString()));
GUI.log(localization.getMessage('dfu_device_flash_info', (self.flash_layout.total_size / 1024).toString()));
if (self.hex.bytes_total > self.available_flash_size) {
GUI.log(chrome.i18n.getMessage('dfu_error_image_size',
GUI.log(localization.getMessage('dfu_error_image_size',
[(self.hex.bytes_total / 1024.0).toFixed(1),
(self.available_flash_size / 1024.0).toFixed(1)]));
self.cleanup();
@ -595,10 +595,10 @@ STM32DFU_protocol.prototype.upload_procedure = function (step) {
self.available_flash_size = firmware_partition_size;
GUI.log(chrome.i18n.getMessage('dfu_device_flash_info', (self.flash_layout.total_size / 1024).toString()));
GUI.log(localization.getMessage('dfu_device_flash_info', (self.flash_layout.total_size / 1024).toString()));
if (self.hex.bytes_total > self.available_flash_size) {
GUI.log(chrome.i18n.getMessage('dfu_error_image_size',
GUI.log(localization.getMessage('dfu_error_image_size',
[(self.hex.bytes_total / 1024.0).toFixed(1),
(self.available_flash_size / 1024.0).toFixed(1)]));
self.cleanup();
@ -631,7 +631,7 @@ STM32DFU_protocol.prototype.upload_procedure = function (step) {
var unprotect = function() {
console.log('Initiate read unprotect');
let messageReadProtected = chrome.i18n.getMessage('stm32ReadProtected');
let messageReadProtected = localization.getMessage('stm32ReadProtected');
GUI.log(messageReadProtected);
TABS.firmware_flasher.flashingMessage(messageReadProtected, TABS.firmware_flasher.FLASH_MESSAGE_TYPES.ACTION);
@ -654,9 +654,9 @@ STM32DFU_protocol.prototype.upload_procedure = function (step) {
self.controlTransfer('in', self.request.GETSTATUS, 0, 0, 6, 0, function (data, error) { // should stall/disconnect
if(error) { // we encounter an error, but this is expected. should be a stall.
console.log('Unprotect memory command ran successfully. Unplug flight controller. Connect again in DFU mode and try flashing again.');
GUI.log(chrome.i18n.getMessage('stm32UnprotectSuccessful'));
GUI.log(localization.getMessage('stm32UnprotectSuccessful'));
let messageUnprotectUnplug = chrome.i18n.getMessage('stm32UnprotectUnplug');
let messageUnprotectUnplug = localization.getMessage('stm32UnprotectUnplug');
GUI.log(messageUnprotectUnplug);
TABS.firmware_flasher.flashingMessage(messageUnprotectUnplug, TABS.firmware_flasher.FLASH_MESSAGE_TYPES.ACTION)
@ -665,8 +665,8 @@ STM32DFU_protocol.prototype.upload_procedure = function (step) {
} else { // unprotecting the flight controller did not work. It did not reboot.
console.log('Failed to execute unprotect memory command');
GUI.log(chrome.i18n.getMessage('stm32UnprotectFailed'));
TABS.firmware_flasher.flashingMessage(chrome.i18n.getMessage('stm32UnprotectFailed'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.INVALID);
GUI.log(localization.getMessage('stm32UnprotectFailed'));
TABS.firmware_flasher.flashingMessage(localization.getMessage('stm32UnprotectFailed'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.INVALID);
console.log(data);
self.cleanup();
}
@ -674,7 +674,7 @@ STM32DFU_protocol.prototype.upload_procedure = function (step) {
}, incr);
} else {
console.log('Failed to initiate unprotect memory command');
let messageUnprotectInitFailed = chrome.i18n.getMessage('stm32UnprotectInitFailed');
let messageUnprotectInitFailed = localization.getMessage('stm32UnprotectInitFailed');
GUI.log(messageUnprotectInitFailed);
TABS.firmware_flasher.flashingMessage(messageUnprotectInitFailed, TABS.firmware_flasher.FLASH_MESSAGE_TYPES.INVALID);
self.cleanup();
@ -695,7 +695,7 @@ STM32DFU_protocol.prototype.upload_procedure = function (step) {
if (data[4] == self.state.dfuUPLOAD_IDLE && ob_data.length == self.chipInfo.option_bytes.total_size) {
console.log('Option bytes read successfully');
console.log('Chip does not appear read protected');
GUI.log(chrome.i18n.getMessage('stm32NotReadProtected'));
GUI.log(localization.getMessage('stm32NotReadProtected'));
// it is pretty safe to continue to erase flash
self.clearStatus(function() {
self.upload_procedure(2);
@ -744,14 +744,14 @@ STM32DFU_protocol.prototype.upload_procedure = function (step) {
// if address load fails with this specific error though, it is very likely bc of read protection
if(loadAddressResponse[4] == self.state.dfuERROR && loadAddressResponse[0] == self.status.errVENDOR) {
// read protected
GUI.log(chrome.i18n.getMessage('stm32AddressLoadFailed'));
GUI.log(localization.getMessage('stm32AddressLoadFailed'));
self.clearStatus(unprotect);
return;
} else if(loadAddressResponse[4] == self.state.dfuDNLOAD_IDLE) {
console.log('Address load for option bytes sector succeeded.');
self.clearStatus(tryReadOB);
} else {
GUI.log(chrome.i18n.getMessage('stm32AddressLoadUnknown'));
GUI.log(localization.getMessage('stm32AddressLoadUnknown'));
self.cleanup();
}
};
@ -793,13 +793,13 @@ STM32DFU_protocol.prototype.upload_procedure = function (step) {
if (erase_pages.length === 0) {
console.log('Aborting, No flash pages to erase');
TABS.firmware_flasher.flashingMessage(chrome.i18n.getMessage('stm32InvalidHex'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.INVALID);
TABS.firmware_flasher.flashingMessage(localization.getMessage('stm32InvalidHex'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.INVALID);
self.cleanup();
break;
}
TABS.firmware_flasher.flashingMessage(chrome.i18n.getMessage('stm32Erase'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.NEUTRAL);
TABS.firmware_flasher.flashingMessage(localization.getMessage('stm32Erase'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.NEUTRAL);
console.log('Executing local chip erase', erase_pages);
var page = 0;
@ -811,7 +811,7 @@ STM32DFU_protocol.prototype.upload_procedure = function (step) {
if(page == erase_pages.length) {
console.log("Erase: complete");
GUI.log(chrome.i18n.getMessage('dfu_erased_kilobytes', (total_erased / 1024).toString()));
GUI.log(localization.getMessage('dfu_erased_kilobytes', (total_erased / 1024).toString()));
self.upload_procedure(4);
} else {
erase_page();
@ -881,7 +881,7 @@ STM32DFU_protocol.prototype.upload_procedure = function (step) {
// upload
// we dont need to clear the state as we are already using DFU_DNLOAD
console.log('Writing data ...');
TABS.firmware_flasher.flashingMessage(chrome.i18n.getMessage('stm32Flashing'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.NEUTRAL);
TABS.firmware_flasher.flashingMessage(localization.getMessage('stm32Flashing'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.NEUTRAL);
var blocks = self.hex.data.length - 1;
var flashing_block = 0;
@ -953,7 +953,7 @@ STM32DFU_protocol.prototype.upload_procedure = function (step) {
case 5:
// verify
console.log('Verifying data ...');
TABS.firmware_flasher.flashingMessage(chrome.i18n.getMessage('stm32Verifying'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.NEUTRAL);
TABS.firmware_flasher.flashingMessage(localization.getMessage('stm32Verifying'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.NEUTRAL);
var blocks = self.hex.data.length - 1;
var reading_block = 0;
@ -1021,14 +1021,14 @@ STM32DFU_protocol.prototype.upload_procedure = function (step) {
if (verify) {
console.log('Programming: SUCCESSFUL');
// update progress bar
TABS.firmware_flasher.flashingMessage(chrome.i18n.getMessage('stm32ProgrammingSuccessful'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.VALID);
TABS.firmware_flasher.flashingMessage(localization.getMessage('stm32ProgrammingSuccessful'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.VALID);
// proceed to next step
self.leave();
} else {
console.log('Programming: FAILED');
// update progress bar
TABS.firmware_flasher.flashingMessage(chrome.i18n.getMessage('stm32ProgrammingFailed'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.INVALID);
TABS.firmware_flasher.flashingMessage(localization.getMessage('stm32ProgrammingFailed'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.INVALID);
// disconnect
self.cleanup();

View file

@ -65,7 +65,7 @@ $(document).ready(function () {
helper.timeout.add('waiting_for_bootup', function waiting_for_bootup() {
MSP.send_message(MSPCodes.MSPV2_INAV_STATUS, false, false, function () {
//noinspection JSUnresolvedVariable
GUI.log(chrome.i18n.getMessage('deviceReady'));
GUI.log(localization.getMessage('deviceReady'));
//noinspection JSValidateTypes
TABS.configuration.initialize(false, $('#content').scrollTop());
});
@ -117,12 +117,11 @@ $(document).ready(function () {
GUI.updateManualPortVisibility();
$portOverride.change(function () {
chrome.storage.local.set({'portOverride': $portOverride.val()});
store.set('portOverride', $portOverride.val());
});
chrome.storage.local.get('portOverride', function (data) {
$portOverride.val(data.portOverride);
});
$portOverride.val(store.get('portOverride', ''));
$port.change(function (target) {
GUI.updateManualPortVisibility();
@ -138,7 +137,7 @@ $(document).ready(function () {
String($port.val());
if (selected_port === 'DFU') {
GUI.log(chrome.i18n.getMessage('dfu_connect_message'));
GUI.log(localization.getMessage('dfu_connect_message'));
}
else if (selected_port != '0') {
if (!clicks) {
@ -147,7 +146,7 @@ $(document).ready(function () {
// lock port select & baud while we are connecting / connected
$('#port, #baud, #delay').prop('disabled', true);
$('div.connect_controls a.connect_state').text(chrome.i18n.getMessage('connecting'));
$('div.connect_controls a.connect_state').text(localization.getMessage('connecting'));
if (selected_port == 'tcp' || selected_port == 'udp') {
CONFIGURATOR.connection.connect($portOverride.val(), {}, onOpen);
@ -210,7 +209,7 @@ $(document).ready(function () {
// reset connect / disconnect button
$('div.connect_controls a.connect').removeClass('active');
$('div.connect_controls a.connect_state').text(chrome.i18n.getMessage('connect'));
$('div.connect_controls a.connect_state').text(localization.getMessage('connect'));
// reset active sensor indicators
sensor_status(0);
@ -236,17 +235,15 @@ function onValidFirmware()
{
MSP.send_message(MSPCodes.MSP_BUILD_INFO, false, false, function () {
googleAnalytics.sendEvent('Firmware', 'Using', CONFIG.buildInfo);
GUI.log(chrome.i18n.getMessage('buildInfoReceived', [CONFIG.buildInfo]));
GUI.log(localization.getMessage('buildInfoReceived', [CONFIG.buildInfo]));
MSP.send_message(MSPCodes.MSP_BOARD_INFO, false, false, function () {
googleAnalytics.sendEvent('Board', 'Using', CONFIG.boardIdentifier + ',' + CONFIG.boardVersion);
GUI.log(chrome.i18n.getMessage('boardInfoReceived', [CONFIG.boardIdentifier, CONFIG.boardVersion]));
GUI.log(localization.getMessage('boardInfoReceived', [CONFIG.boardIdentifier, CONFIG.boardVersion]));
MSP.send_message(MSPCodes.MSP_UID, false, false, function () {
GUI.log(chrome.i18n.getMessage('uniqueDeviceIdReceived', [CONFIG.uid[0].toString(16) + CONFIG.uid[1].toString(16) + CONFIG.uid[2].toString(16)]));
GUI.log(localization.getMessage('uniqueDeviceIdReceived', [CONFIG.uid[0].toString(16) + CONFIG.uid[1].toString(16) + CONFIG.uid[2].toString(16)]));
// continue as usually
CONFIGURATOR.connectionValid = true;
@ -266,7 +263,7 @@ function onValidFirmware()
function onInvalidFirmwareVariant()
{
GUI.log(chrome.i18n.getMessage('firmwareVariantNotSupported'));
GUI.log(localization.getMessage('firmwareVariantNotSupported'));
CONFIGURATOR.connectionValid = true; // making it possible to open the CLI tab
GUI.allowedTabs = ['cli'];
onConnect();
@ -275,7 +272,7 @@ function onInvalidFirmwareVariant()
function onInvalidFirmwareVersion()
{
GUI.log(chrome.i18n.getMessage('firmwareVersionNotSupported', [CONFIGURATOR.minfirmwareVersionAccepted, CONFIGURATOR.maxFirmwareVersionAccepted]));
GUI.log(localization.getMessage('firmwareVersionNotSupported', [CONFIGURATOR.minfirmwareVersionAccepted, CONFIGURATOR.maxFirmwareVersionAccepted]));
CONFIGURATOR.connectionValid = true; // making it possible to open the CLI tab
GUI.allowedTabs = ['cli'];
onConnect();
@ -283,7 +280,7 @@ function onInvalidFirmwareVersion()
}
function onBleNotSupported() {
GUI.log(chrome.i18n.getMessage('connectionBleNotSupported'));
GUI.log(localization.getMessage('connectionBleNotSupported'));
CONFIGURATOR.connection.abort();
}
@ -291,7 +288,7 @@ function onBleNotSupported() {
function onOpen(openInfo) {
if (FC.restartRequired) {
GUI_control.prototype.log("<span style='color: red; font-weight: bolder'><strong>" + chrome.i18n.getMessage("illegalStateRestartRequired") + "</strong></span>");
GUI_control.prototype.log("<span style='color: red; font-weight: bolder'><strong>" + localization.getMessage("illegalStateRestartRequired") + "</strong></span>");
$('div.connect_controls a').click(); // disconnect
return;
}
@ -303,30 +300,31 @@ function onOpen(openInfo) {
// reset connecting_to
GUI.connecting_to = false;
GUI.log(chrome.i18n.getMessage('serialPortOpened', [openInfo.connectionId]));
GUI.log(localization.getMessage('serialPortOpened', [openInfo.connectionId]));
// save selected port with chrome.storage if the port differs
chrome.storage.local.get('last_used_port', function (result) {
if (result.last_used_port) {
if (result.last_used_port != GUI.connected_to) {
// last used port doesn't match the one found in local db, we will store the new one
chrome.storage.local.set({'last_used_port': GUI.connected_to});
}
} else {
// variable isn't stored yet, saving
chrome.storage.local.set({'last_used_port': GUI.connected_to});
var last_used_port = store.get('last_used_port', false);
if (last_used_port) {
if (last_used_port != GUI.connected_to) {
// last used port doesn't match the one found in local db, we will store the new one
store.set('last_used_port', GUI.connected_to);
}
});
} else {
// variable isn't stored yet, saving
store.set('last_used_port', GUI.connected_to);
}
chrome.storage.local.set({last_used_bps: CONFIGURATOR.connection.bitrate});
chrome.storage.local.set({wireless_mode_enabled: $('#wireless-mode').is(":checked")});
store.set('last_used_bps', CONFIGURATOR.connection.bitrate);
store.set('wireless_mode_enabled', $('#wireless-mode').is(":checked"));
CONFIGURATOR.connection.addOnReceiveListener(read_serial);
/*
// disconnect after 10 seconds with error if we don't get IDENT data
helper.timeout.add('connecting', function () {
if (!CONFIGURATOR.connectionValid) {
GUI.log(chrome.i18n.getMessage('noConfigurationReceived'));
GUI.log(localization.getMessage('noConfigurationReceived'));
helper.mspQueue.flush();
helper.mspQueue.freeHardLock();
@ -336,6 +334,7 @@ function onOpen(openInfo) {
$('div.connect_controls a').click(); // disconnect
}
}, 10000);
*/
FC.resetState();
@ -345,18 +344,18 @@ function onOpen(openInfo) {
MSP.send_message(MSPCodes.MSP_API_VERSION, false, false, function () {
if (CONFIG.apiVersion === "0.0.0") {
GUI_control.prototype.log("<span style='color: red; font-weight: bolder'><strong>" + chrome.i18n.getMessage("illegalStateRestartRequired") + "</strong></span>");
GUI_control.prototype.log("<span style='color: red; font-weight: bolder'><strong>" + localization.getMessage("illegalStateRestartRequired") + "</strong></span>");
FC.restartRequired = true;
return;
}
GUI.log(chrome.i18n.getMessage('apiVersionReceived', [CONFIG.apiVersion]));
GUI.log(localization.getMessage('apiVersionReceived', [CONFIG.apiVersion]));
MSP.send_message(MSPCodes.MSP_FC_VARIANT, false, false, function () {
if (CONFIG.flightControllerIdentifier == 'INAV') {
MSP.send_message(MSPCodes.MSP_FC_VERSION, false, false, function () {
googleAnalytics.sendEvent('Firmware', 'Variant', CONFIG.flightControllerIdentifier + ',' + CONFIG.flightControllerVersion);
GUI.log(chrome.i18n.getMessage('fcInfoReceived', [CONFIG.flightControllerIdentifier, CONFIG.flightControllerVersion]));
GUI.log(localization.getMessage('fcInfoReceived', [CONFIG.flightControllerIdentifier, CONFIG.flightControllerVersion]));
if (semver.gte(CONFIG.flightControllerVersion, CONFIGURATOR.minfirmwareVersionAccepted) && semver.lt(CONFIG.flightControllerVersion, CONFIGURATOR.maxFirmwareVersionAccepted)) {
if (CONFIGURATOR.connection.type == ConnectionType.BLE && semver.lt(CONFIG.flightControllerVersion, "5.0.0")) {
onBleNotSupported();
@ -379,11 +378,11 @@ function onOpen(openInfo) {
});
} else {
console.log('Failed to open serial port');
GUI.log(chrome.i18n.getMessage('serialPortOpenFail'));
GUI.log(localization.getMessage('serialPortOpenFail'));
var $connectButton = $('#connectbutton');
$connectButton.find('.connect_state').text(chrome.i18n.getMessage('connect'));
$connectButton.find('.connect_state').text(localization.getMessage('connect'));
$connectButton.find('.connect').removeClass('active');
// unlock port select & baud
@ -396,7 +395,7 @@ function onOpen(openInfo) {
function onConnect() {
helper.timeout.remove('connecting'); // kill connecting timer
$('#connectbutton a.connect_state').text(chrome.i18n.getMessage('disconnect')).addClass('active');
$('#connectbutton a.connect_state').text(localization.getMessage('disconnect')).addClass('active');
$('#connectbutton a.connect').addClass('active');
$('.mode-disconnected').hide();
$('.mode-connected').show();
@ -434,9 +433,9 @@ function onConnect() {
function onClosed(result) {
if (result) { // All went as expected
GUI.log(chrome.i18n.getMessage('serialPortClosedOk'));
GUI.log(localization.getMessage('serialPortClosedOk'));
} else { // Something went wrong
GUI.log(chrome.i18n.getMessage('serialPortClosedFail'));
GUI.log(localization.getMessage('serialPortClosedFail'));
}
$('.mode-connected').hide();

View file

@ -6,7 +6,7 @@ var Settings = (function () {
self.fillSelectOption = function(s, ii) {
var name = (s.setting.table ? s.setting.table.values[ii] : null);
if (name) {
var localizedName = chrome.i18n.getMessage(name);
var localizedName = localization.getMessage(name);
if (localizedName) {
name = localizedName;
}
@ -26,7 +26,7 @@ var Settings = (function () {
$('[data-setting!=""][data-setting]').each(function() {
inputs.push($(this));
});
return Promise.mapSeries(inputs, function (input, ii) {
return mapSeries(inputs, function (input, ii) {
var settingName = input.data('setting');
var inputUnit = input.data('unit');
@ -580,7 +580,7 @@ var Settings = (function () {
$('[data-setting!=""][data-setting]').each(function() {
inputs.push($(this));
});
return Promise.mapSeries(inputs, function (input, ii) {
return mapSeries(inputs, function (input, ii) {
return self.saveInput(input);
});
};
@ -602,7 +602,7 @@ var Settings = (function () {
helpIcons.push($(this));
});
return Promise.mapSeries(helpIcons, function(helpIcon, ii) {
return mapSeries(helpIcons, function(helpIcon, ii) {
let forAtt = helpIcon.attr('for');
if (typeof forAtt !== "undefined" && forAtt !== "") {

View file

@ -124,22 +124,25 @@ var Ser2TCP = {
},
getDevices: function(callback) {
chrome.serial.getDevices((devices_array) => {
SerialPort.list().then((ports, error) => {
var devices = [];
devices_array.forEach((device) => {
if (GUI.operating_system == 'Windows') {
var m = device.path.match(/COM\d?\d/g)
if (error) {
GUI.log("Unable to list serial ports.");
} else {
ports.forEach((device) => {
if (GUI.operating_system == 'Windows') {
var m = device.path.match(/COM\d?\d/g)
if (m)
devices.push(m[0]);
} else {
if (device.displayName != null) {
var m = device.path.match(/\/dev\/.*/)
if (m)
devices.push(m[0]);
devices.push(m[0]);
} else {
if (device.displayName != null) {
var m = device.path.match(/\/dev\/.*/)
if (m)
devices.push(m[0]);
}
}
}
});
});
}
callback(devices);
});
},

View file

@ -139,7 +139,7 @@ let Waypoint = function (number, action, lat, lon, alt=0, p1=0, p2=0, p3=0, endM
self.getElevation = async function (globalSettings) {
let elevation = "N/A";
if (globalSettings.mapProviderType == 'bing') {
let elevationEarthModel = $('#elevationEarthModel').prop("checked") ? "ellipsoid" : "sealevel";
let elevationEarthModel = $('#elevationEarthModel').prop("checked") ? "sealevel" : "ellipsoid";
const response = await fetch('http://dev.virtualearth.net/REST/v1/Elevation/List?points='+self.getLatMap()+','+self.getLonMap()+'&heights='+elevationEarthModel+'&key='+globalSettings.mapApiKey);
const myJson = await response.json();