mirror of
https://github.com/betaflight/betaflight-configurator.git
synced 2025-07-16 21:05:30 +03:00
Fix critical and major bugs from Sonar in JS files
This commit is contained in:
parent
377149f06a
commit
c8b4958e8c
8 changed files with 93 additions and 98 deletions
|
@ -11,7 +11,6 @@
|
||||||
|
|
||||||
|
|
||||||
.dropdown {
|
.dropdown {
|
||||||
|
|
||||||
display: inline-block;
|
display: inline-block;
|
||||||
position: relative;
|
position: relative;
|
||||||
overflow: hidden;
|
overflow: hidden;
|
||||||
|
@ -26,14 +25,10 @@
|
||||||
width:99%;
|
width:99%;
|
||||||
margin-bottom:7px;
|
margin-bottom:7px;
|
||||||
border: 1px solid;
|
border: 1px solid;
|
||||||
border-color: #ccc #ccc #ccc;
|
border-color: #ccc #ccc #ccc;
|
||||||
border-radius: 3px;
|
border-radius: 3px;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
.dropdown:before, .dropdown:after {
|
.dropdown:before, .dropdown:after {
|
||||||
content: '';
|
content: '';
|
||||||
position: absolute;
|
position: absolute;
|
||||||
|
@ -46,12 +41,14 @@
|
||||||
border-color: #888 transparent;
|
border-color: #888 transparent;
|
||||||
pointer-events: none;
|
pointer-events: none;
|
||||||
}
|
}
|
||||||
|
|
||||||
.dropdown:before {
|
.dropdown:before {
|
||||||
border-bottom-style: solid;
|
border-bottom-style: solid;
|
||||||
border-top: none;
|
border-top: none;
|
||||||
margin-top: -2px;
|
margin-top: -2px;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
.dropdown:after {
|
.dropdown:after {
|
||||||
margin-top: 5px;
|
margin-top: 5px;
|
||||||
border-top-style: solid;
|
border-top-style: solid;
|
||||||
|
@ -63,7 +60,6 @@
|
||||||
overflow:visible;
|
overflow:visible;
|
||||||
width: 100%;
|
width: 100%;
|
||||||
margin-top:0px;
|
margin-top:0px;
|
||||||
padding-bottom:0px;
|
|
||||||
padding: 1px 8px 6px 5px;
|
padding: 1px 8px 6px 5px;
|
||||||
height: 23px;
|
height: 23px;
|
||||||
line-height: 20px;
|
line-height: 20px;
|
||||||
|
@ -77,9 +73,8 @@
|
||||||
border: 0;
|
border: 0;
|
||||||
border-radius: 0;
|
border-radius: 0;
|
||||||
-webkit-appearance: none;
|
-webkit-appearance: none;
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
.dropdown-select:focus {
|
.dropdown-select:focus {
|
||||||
z-index: 3;
|
z-index: 3;
|
||||||
width: 90%;
|
width: 90%;
|
||||||
|
@ -87,9 +82,9 @@
|
||||||
outline: 0px solid #49aff2;
|
outline: 0px solid #49aff2;
|
||||||
outline: 0px solid -webkit-focus-ring-color;
|
outline: 0px solid -webkit-focus-ring-color;
|
||||||
outline-offset: 5px;
|
outline-offset: 5px;
|
||||||
|
|
||||||
height:25px;
|
height:25px;
|
||||||
}
|
}
|
||||||
|
|
||||||
.dropdown-select > option {
|
.dropdown-select > option {
|
||||||
margin: 3px;
|
margin: 3px;
|
||||||
padding: 6px 8px;
|
padding: 6px 8px;
|
||||||
|
@ -97,24 +92,25 @@
|
||||||
background: #f2f2f2;
|
background: #f2f2f2;
|
||||||
border-radius: 3px;
|
border-radius: 3px;
|
||||||
cursor: pointer;
|
cursor: pointer;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Fix for IE 8 putting the arrows behind the select element. */
|
/* Fix for IE 8 putting the arrows behind the select element. */
|
||||||
.lt-ie9 .dropdown {
|
.lt-ie9 .dropdown {
|
||||||
z-index: 1;
|
z-index: 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
.lt-ie9 .dropdown-select {
|
.lt-ie9 .dropdown-select {
|
||||||
z-index: -1;
|
z-index: -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
.lt-ie9 .dropdown-select:focus {
|
.lt-ie9 .dropdown-select:focus {
|
||||||
z-index: 3;
|
z-index: 3;
|
||||||
}
|
}
|
||||||
|
|
||||||
.dropdown-dark {
|
.dropdown-dark {
|
||||||
background: #636363; /* NEW2 */
|
background: #636363; /* NEW2 */
|
||||||
background: #3e403f; /* NEW */
|
background: #3e403f; /* NEW */
|
||||||
|
|
||||||
border-color: #111 #0a0a0a black;
|
border-color: #111 #0a0a0a black;
|
||||||
background-image: -webkit-linear-gradient(top, transparent, rgba(0, 0, 0, 0.4));
|
background-image: -webkit-linear-gradient(top, transparent, rgba(0, 0, 0, 0.4));
|
||||||
background-image: -moz-linear-gradient(top, transparent, rgba(0, 0, 0, 0.4));
|
background-image: -moz-linear-gradient(top, transparent, rgba(0, 0, 0, 0.4));
|
||||||
|
@ -123,28 +119,28 @@
|
||||||
-webkit-box-shadow: inset 0 1px rgba(255, 255, 255, 0.1), 0 1px 1px rgba(0, 0, 0, 0.2);
|
-webkit-box-shadow: inset 0 1px rgba(255, 255, 255, 0.1), 0 1px 1px rgba(0, 0, 0, 0.2);
|
||||||
box-shadow: inset 0 1px rgba(255, 255, 255, 0.1), 0 1px 1px rgba(0, 0, 0, 0.2);
|
box-shadow: inset 0 1px rgba(255, 255, 255, 0.1), 0 1px 1px rgba(0, 0, 0, 0.2);
|
||||||
color:#a6a6a6;
|
color:#a6a6a6;
|
||||||
text-shadow:0px 1px rgba(0, 0, 0, 0.25);
|
text-shadow:0px 1px rgba(0, 0, 0, 0.25);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
.dropdown-dark:before {
|
.dropdown-dark:before {
|
||||||
border-bottom-color: #aaa;
|
border-bottom-color: #aaa;
|
||||||
}
|
}
|
||||||
|
|
||||||
.dropdown-dark:after {
|
.dropdown-dark:after {
|
||||||
border-top-color: #aaa;
|
border-top-color: #aaa;
|
||||||
}
|
}
|
||||||
|
|
||||||
.dropdown-dark .dropdown-select {
|
.dropdown-dark .dropdown-select {
|
||||||
color: #a6a6a6;
|
color: #a6a6a6;
|
||||||
text-shadow: 0 1px black;
|
text-shadow: 0 1px black;
|
||||||
/* Fallback for IE 8 */
|
/* Fallback for IE 8 */
|
||||||
background: #444;
|
background: #444;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
.dropdown-dark .dropdown-select:focus {
|
.dropdown-dark .dropdown-select:focus {
|
||||||
color: #fff;
|
color: #fff;
|
||||||
}
|
}
|
||||||
|
|
||||||
.dropdown-dark .dropdown-select > option {
|
.dropdown-dark .dropdown-select > option {
|
||||||
background: #56ab1a;
|
background: #56ab1a;
|
||||||
text-shadow: 0 1px rgba(0, 0, 0, 0.4);
|
text-shadow: 0 1px rgba(0, 0, 0, 0.4);
|
||||||
|
|
|
@ -694,7 +694,6 @@
|
||||||
|
|
||||||
.tabarea {
|
.tabarea {
|
||||||
width: calc(100% - 22px);
|
width: calc(100% - 22px);
|
||||||
padding-left: 10px;
|
|
||||||
position: relative;
|
position: relative;
|
||||||
padding: 10px;
|
padding: 10px;
|
||||||
border: 1px solid var(--subtleAccent);
|
border: 1px solid var(--subtleAccent);
|
||||||
|
|
|
@ -54,7 +54,7 @@ CliAutoComplete.initialize = function($textarea, sendLine, writeToOutput) {
|
||||||
analytics.sendEvent(analytics.EVENT_CATEGORIES.APPLICATION, 'CliAutoComplete', this.configEnabled);
|
analytics.sendEvent(analytics.EVENT_CATEGORIES.APPLICATION, 'CliAutoComplete', this.configEnabled);
|
||||||
|
|
||||||
this.$textarea = $textarea;
|
this.$textarea = $textarea;
|
||||||
this.forceOpen = false,
|
this.forceOpen = false;
|
||||||
this.sendLine = sendLine;
|
this.sendLine = sendLine;
|
||||||
this.writeToOutput = writeToOutput;
|
this.writeToOutput = writeToOutput;
|
||||||
this.cleanup();
|
this.cleanup();
|
||||||
|
|
|
@ -8,12 +8,12 @@ var GUI_control = function () {
|
||||||
this.connecting_to = false;
|
this.connecting_to = false;
|
||||||
this.connected_to = false;
|
this.connected_to = false;
|
||||||
this.connect_lock = false;
|
this.connect_lock = false;
|
||||||
this.active_tab;
|
this.active_tab = null;
|
||||||
this.tab_switch_in_progress = false;
|
this.tab_switch_in_progress = false;
|
||||||
this.operating_system;
|
this.operating_system = null;
|
||||||
this.interval_array = [];
|
this.interval_array = [];
|
||||||
this.timeout_array = [];
|
this.timeout_array = [];
|
||||||
|
|
||||||
this.defaultAllowedTabsWhenDisconnected = [
|
this.defaultAllowedTabsWhenDisconnected = [
|
||||||
'landing',
|
'landing',
|
||||||
'changelog',
|
'changelog',
|
||||||
|
@ -352,14 +352,14 @@ GUI_control.prototype.content_ready = function (callback) {
|
||||||
|
|
||||||
GUI_control.prototype.selectDefaultTabWhenConnected = function() {
|
GUI_control.prototype.selectDefaultTabWhenConnected = function() {
|
||||||
ConfigStorage.get(['rememberLastTab', 'lastTab'], function (result) {
|
ConfigStorage.get(['rememberLastTab', 'lastTab'], function (result) {
|
||||||
if (!(result.rememberLastTab
|
if (!(result.rememberLastTab
|
||||||
&& !!result.lastTab
|
&& !!result.lastTab
|
||||||
&& result.lastTab.substring(4) != "cli")) {
|
&& result.lastTab.substring(4) != "cli")) {
|
||||||
$('#tabs ul.mode-connected .tab_setup a').click();
|
$('#tabs ul.mode-connected .tab_setup a').click();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
$("#tabs ul.mode-connected ." + result.lastTab + " a").click();
|
$("#tabs ul.mode-connected ." + result.lastTab + " a").click();
|
||||||
});
|
});
|
||||||
};
|
};
|
||||||
|
|
||||||
GUI_control.prototype.isChromeApp = function () {
|
GUI_control.prototype.isChromeApp = function () {
|
||||||
|
|
|
@ -8,19 +8,19 @@
|
||||||
'use strict';
|
'use strict';
|
||||||
|
|
||||||
var STM32_protocol = function () {
|
var STM32_protocol = function () {
|
||||||
this.baud;
|
this.baud = null;
|
||||||
this.options = {};
|
this.options = {};
|
||||||
this.callback; // ref
|
this.callback = null;
|
||||||
this.hex; // ref
|
this.hex = null;
|
||||||
this.verify_hex;
|
this.verify_hex = [];
|
||||||
|
|
||||||
this.receive_buffer;
|
this.receive_buffer = [];
|
||||||
|
|
||||||
this.bytes_to_read = 0; // ref
|
this.bytes_to_read = 0;
|
||||||
this.read_callback; // ref
|
this.read_callback = null;
|
||||||
|
|
||||||
this.upload_time_start;
|
this.upload_time_start = 0;
|
||||||
this.upload_process_alive;
|
this.upload_process_alive = false;
|
||||||
|
|
||||||
this.msp_connector = new MSPConnectorImpl();
|
this.msp_connector = new MSPConnectorImpl();
|
||||||
|
|
||||||
|
@ -113,7 +113,7 @@ STM32_protocol.prototype.connect = function (port, baud, hex, options, callback)
|
||||||
GUI.connect_lock = false;
|
GUI.connect_lock = false;
|
||||||
GUI.log(i18n.getMessage('serialPortOpenFail'));
|
GUI.log(i18n.getMessage('serialPortOpenFail'));
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
console.log('Using legacy reboot method');
|
console.log('Using legacy reboot method');
|
||||||
|
|
||||||
|
@ -138,11 +138,11 @@ STM32_protocol.prototype.connect = function (port, baud, hex, options, callback)
|
||||||
};
|
};
|
||||||
|
|
||||||
var onConnectHandler = function () {
|
var onConnectHandler = function () {
|
||||||
|
|
||||||
GUI.log(i18n.getMessage('apiVersionReceived', [CONFIG.apiVersion]));
|
GUI.log(i18n.getMessage('apiVersionReceived', [CONFIG.apiVersion]));
|
||||||
|
|
||||||
if (semver.lt(CONFIG.apiVersion, "1.42.0")) {
|
if (semver.lt(CONFIG.apiVersion, "1.42.0")) {
|
||||||
|
|
||||||
self.msp_connector.disconnect(function (disconnectionResult) {
|
self.msp_connector.disconnect(function (disconnectionResult) {
|
||||||
|
|
||||||
// need some time for the port to be closed, serial port does not open if tried immediately
|
// need some time for the port to be closed, serial port does not open if tried immediately
|
||||||
|
@ -163,14 +163,14 @@ STM32_protocol.prototype.connect = function (port, baud, hex, options, callback)
|
||||||
console.log('no flash bootloader detected');
|
console.log('no flash bootloader detected');
|
||||||
rebootMode = 1; // MSP_REBOOT_BOOTLOADER_ROM;
|
rebootMode = 1; // MSP_REBOOT_BOOTLOADER_ROM;
|
||||||
}
|
}
|
||||||
|
|
||||||
var buffer = [];
|
var buffer = [];
|
||||||
buffer.push8(rebootMode);
|
buffer.push8(rebootMode);
|
||||||
MSP.send_message(MSPCodes.MSP_SET_REBOOT, buffer, function() {
|
MSP.send_message(MSPCodes.MSP_SET_REBOOT, buffer, function() {
|
||||||
|
|
||||||
// if firmware doesn't flush MSP/serial send buffers and gracefully shutdown VCP connections we won't get a reply, so don't wait for it.
|
// if firmware doesn't flush MSP/serial send buffers and gracefully shutdown VCP connections we won't get a reply, so don't wait for it.
|
||||||
|
|
||||||
self.msp_connector.disconnect(function (disconnectionResult) {
|
self.msp_connector.disconnect(function (disconnectionResult) {
|
||||||
if (disconnectionResult) {
|
if (disconnectionResult) {
|
||||||
// delay to allow board to boot in bootloader mode
|
// delay to allow board to boot in bootloader mode
|
||||||
// required to detect if a DFU device appears
|
// required to detect if a DFU device appears
|
||||||
|
@ -179,7 +179,7 @@ STM32_protocol.prototype.connect = function (port, baud, hex, options, callback)
|
||||||
GUI.connect_lock = false;
|
GUI.connect_lock = false;
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
|
|
||||||
}, function () {
|
}, function () {
|
||||||
console.log('Reboot request recevied by device');
|
console.log('Reboot request recevied by device');
|
||||||
});
|
});
|
||||||
|
@ -190,17 +190,17 @@ STM32_protocol.prototype.connect = function (port, baud, hex, options, callback)
|
||||||
var onTimeoutHandler = function() {
|
var onTimeoutHandler = function() {
|
||||||
GUI.connect_lock = false;
|
GUI.connect_lock = false;
|
||||||
console.log('Looking for capabilities via MSP failed');
|
console.log('Looking for capabilities via MSP failed');
|
||||||
|
|
||||||
TABS.firmware_flasher.flashingMessage(i18n.getMessage('stm32RebootingToBootloaderFailed'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.INVALID);
|
TABS.firmware_flasher.flashingMessage(i18n.getMessage('stm32RebootingToBootloaderFailed'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.INVALID);
|
||||||
}
|
}
|
||||||
|
|
||||||
var onFailureHandler = function() {
|
var onFailureHandler = function() {
|
||||||
GUI.connect_lock = false;
|
GUI.connect_lock = false;
|
||||||
};
|
};
|
||||||
|
|
||||||
GUI.connect_lock = true;
|
GUI.connect_lock = true;
|
||||||
TABS.firmware_flasher.flashingMessage(i18n.getMessage('stm32RebootingToBootloader'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.NEUTRAL);
|
TABS.firmware_flasher.flashingMessage(i18n.getMessage('stm32RebootingToBootloader'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.NEUTRAL);
|
||||||
|
|
||||||
self.msp_connector.connect(self.port, self.options.reboot_baud, onConnectHandler, onTimeoutHandler, onFailureHandler);
|
self.msp_connector.connect(self.port, self.options.reboot_baud, onConnectHandler, onTimeoutHandler, onFailureHandler);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
@ -282,18 +282,18 @@ STM32_protocol.prototype.retrieve = function (n_bytes, callback) {
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
// Array = array of bytes that will be send over serial
|
// bytes_to_send = array of bytes that will be send over serial
|
||||||
// bytes_to_read = received bytes necessary to trigger read_callback
|
// bytes_to_read = received bytes necessary to trigger read_callback
|
||||||
// callback = function that will be executed after received bytes = bytes_to_read
|
// callback = function that will be executed after received bytes = bytes_to_read
|
||||||
STM32_protocol.prototype.send = function (Array, bytes_to_read, callback) {
|
STM32_protocol.prototype.send = function (bytes_to_send, bytes_to_read, callback) {
|
||||||
// flip flag
|
// flip flag
|
||||||
this.upload_process_alive = true;
|
this.upload_process_alive = true;
|
||||||
|
|
||||||
var bufferOut = new ArrayBuffer(Array.length);
|
var bufferOut = new ArrayBuffer(bytes_to_send.length);
|
||||||
var bufferView = new Uint8Array(bufferOut);
|
var bufferView = new Uint8Array(bufferOut);
|
||||||
|
|
||||||
// set Array values inside bufferView (alternative to for loop)
|
// set bytes_to_send values inside bufferView (alternative to for loop)
|
||||||
bufferView.set(Array);
|
bufferView.set(bytes_to_send);
|
||||||
|
|
||||||
// update references
|
// update references
|
||||||
this.bytes_to_read = bytes_to_read;
|
this.bytes_to_read = bytes_to_read;
|
||||||
|
@ -311,7 +311,7 @@ STM32_protocol.prototype.send = function (Array, bytes_to_read, callback) {
|
||||||
// result = true/false
|
// result = true/false
|
||||||
STM32_protocol.prototype.verify_response = function (val, data) {
|
STM32_protocol.prototype.verify_response = function (val, data) {
|
||||||
var self = this;
|
var self = this;
|
||||||
|
|
||||||
if (val != data[0]) {
|
if (val != data[0]) {
|
||||||
var message = 'STM32 Communication failed, wrong response, expected: ' + val + ' (0x' + val.toString(16) + ') received: ' + data[0] + ' (0x' + data[0].toString(16) + ')';
|
var message = 'STM32 Communication failed, wrong response, expected: ' + val + ' (0x' + val.toString(16) + ') received: ' + data[0] + ' (0x' + data[0].toString(16) + ')';
|
||||||
console.error(message);
|
console.error(message);
|
||||||
|
@ -501,14 +501,14 @@ STM32_protocol.prototype.upload_procedure = function (step) {
|
||||||
|
|
||||||
if (self.useExtendedErase) {
|
if (self.useExtendedErase) {
|
||||||
if (self.options.erase_chip) {
|
if (self.options.erase_chip) {
|
||||||
|
|
||||||
var message = 'Executing global chip erase (via extended erase)';
|
var message = 'Executing global chip erase (via extended erase)';
|
||||||
console.log(message);
|
console.log(message);
|
||||||
TABS.firmware_flasher.flashingMessage(i18n.getMessage('stm32GlobalEraseExtended'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.NEUTRAL);
|
TABS.firmware_flasher.flashingMessage(i18n.getMessage('stm32GlobalEraseExtended'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.NEUTRAL);
|
||||||
|
|
||||||
self.send([self.command.extended_erase, 0xBB], 1, function (reply) {
|
self.send([self.command.extended_erase, 0xBB], 1, function (reply) {
|
||||||
if (self.verify_response(self.status.ACK, reply)) {
|
if (self.verify_response(self.status.ACK, reply)) {
|
||||||
self.send( [0xFF, 0xFF, 0x00], 1, function (reply) {
|
self.send( [0xFF, 0xFF, 0x00], 1, function (reply) {
|
||||||
if (self.verify_response(self.status.ACK, reply)) {
|
if (self.verify_response(self.status.ACK, reply)) {
|
||||||
console.log('Executing global chip extended erase: done');
|
console.log('Executing global chip extended erase: done');
|
||||||
self.upload_procedure(5);
|
self.upload_procedure(5);
|
||||||
|
@ -516,15 +516,15 @@ STM32_protocol.prototype.upload_procedure = function (step) {
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
var message = 'Executing local erase (via extended erase)';
|
var message = 'Executing local erase (via extended erase)';
|
||||||
console.log(message);
|
console.log(message);
|
||||||
TABS.firmware_flasher.flashingMessage(i18n.getMessage('stm32LocalEraseExtended'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.NEUTRAL);
|
TABS.firmware_flasher.flashingMessage(i18n.getMessage('stm32LocalEraseExtended'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.NEUTRAL);
|
||||||
|
|
||||||
self.send([self.command.extended_erase, 0xBB], 1, function (reply) {
|
self.send([self.command.extended_erase, 0xBB], 1, function (reply) {
|
||||||
if (self.verify_response(self.status.ACK, reply)) {
|
if (self.verify_response(self.status.ACK, reply)) {
|
||||||
|
|
||||||
// For reference: https://code.google.com/p/stm32flash/source/browse/stm32.c#723
|
// For reference: https://code.google.com/p/stm32flash/source/browse/stm32.c#723
|
||||||
|
|
||||||
var max_address = self.hex.data[self.hex.data.length - 1].address + self.hex.data[self.hex.data.length - 1].bytes - 0x8000000,
|
var max_address = self.hex.data[self.hex.data.length - 1].address + self.hex.data[self.hex.data.length - 1].bytes - 0x8000000,
|
||||||
|
@ -541,18 +541,18 @@ STM32_protocol.prototype.upload_procedure = function (step) {
|
||||||
buff.push(pg_byte);
|
buff.push(pg_byte);
|
||||||
checksum ^= pg_byte;
|
checksum ^= pg_byte;
|
||||||
|
|
||||||
|
|
||||||
for (var i = 0; i < erase_pages_n; i++) {
|
for (var i = 0; i < erase_pages_n; i++) {
|
||||||
pg_byte = i >> 8;
|
pg_byte = i >> 8;
|
||||||
buff.push(pg_byte);
|
buff.push(pg_byte);
|
||||||
checksum ^= pg_byte;
|
checksum ^= pg_byte;
|
||||||
pg_byte = i & 0xFF;
|
pg_byte = i & 0xFF;
|
||||||
buff.push(pg_byte);
|
buff.push(pg_byte);
|
||||||
checksum ^= pg_byte;
|
checksum ^= pg_byte;
|
||||||
}
|
}
|
||||||
|
|
||||||
buff.push(checksum);
|
buff.push(checksum);
|
||||||
console.log('Erasing. pages: 0x00 - 0x' + erase_pages_n.toString(16) + ', checksum: 0x' + checksum.toString(16));
|
console.log('Erasing. pages: 0x00 - 0x' + erase_pages_n.toString(16) + ', checksum: 0x' + checksum.toString(16));
|
||||||
|
|
||||||
self.send(buff, 1, function (reply) {
|
self.send(buff, 1, function (reply) {
|
||||||
if (self.verify_response(self.status.ACK, reply)) {
|
if (self.verify_response(self.status.ACK, reply)) {
|
||||||
|
@ -563,8 +563,8 @@ STM32_protocol.prototype.upload_procedure = function (step) {
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -586,7 +586,7 @@ STM32_protocol.prototype.upload_procedure = function (step) {
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
} else {
|
} else {
|
||||||
var message = 'Executing local erase';
|
var message = 'Executing local erase';
|
||||||
console.log(message);
|
console.log(message);
|
||||||
TABS.firmware_flasher.flashingMessage(i18n.getMessage('stm32LocalErase'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.NEUTRAL);
|
TABS.firmware_flasher.flashingMessage(i18n.getMessage('stm32LocalErase'), TABS.firmware_flasher.FLASH_MESSAGE_TYPES.NEUTRAL);
|
||||||
|
|
||||||
|
|
|
@ -13,9 +13,9 @@
|
||||||
'use strict';
|
'use strict';
|
||||||
|
|
||||||
var STM32DFU_protocol = function () {
|
var STM32DFU_protocol = function () {
|
||||||
this.callback; // ref
|
this.callback = null;
|
||||||
this.hex; // ref
|
this.hex = null;
|
||||||
this.verify_hex;
|
this.verify_hex = [];
|
||||||
|
|
||||||
this.handle = null; // connection handle
|
this.handle = null; // connection handle
|
||||||
|
|
||||||
|
|
|
@ -64,7 +64,7 @@ SYM.loadSymbols = function() {
|
||||||
SYM.ROLL = 0x14;
|
SYM.ROLL = 0x14;
|
||||||
|
|
||||||
/* Versions before Betaflight 4.1 use font V1
|
/* Versions before Betaflight 4.1 use font V1
|
||||||
* To maintain this list at minimum, we only add here:
|
* To maintain this list at minimum, we only add here:
|
||||||
* - Symbols used in this versions
|
* - Symbols used in this versions
|
||||||
* - That were moved or didn't exist in the font file
|
* - That were moved or didn't exist in the font file
|
||||||
*/
|
*/
|
||||||
|
@ -277,7 +277,7 @@ OSD.getNumberOfProfiles = function() {
|
||||||
|
|
||||||
OSD.getCurrentPreviewProfile = function() {
|
OSD.getCurrentPreviewProfile = function() {
|
||||||
let osdprofile_e = $('.osdprofile-selector');
|
let osdprofile_e = $('.osdprofile-selector');
|
||||||
if (osdprofile_e) {
|
if (osdprofile_e.length > 0) {
|
||||||
return osdprofile_e.val();
|
return osdprofile_e.val();
|
||||||
} else {
|
} else {
|
||||||
return 0;
|
return 0;
|
||||||
|
@ -1598,7 +1598,7 @@ OSD.chooseFields = function () {
|
||||||
F.GPS_RESCUE_DISABLED
|
F.GPS_RESCUE_DISABLED
|
||||||
]);
|
]);
|
||||||
}
|
}
|
||||||
|
|
||||||
OSD.constants.TIMER_TYPES = [
|
OSD.constants.TIMER_TYPES = [
|
||||||
'ON_TIME',
|
'ON_TIME',
|
||||||
'TOTAL_ARMED_TIME',
|
'TOTAL_ARMED_TIME',
|
||||||
|
@ -1670,7 +1670,7 @@ OSD.msp = {
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
|
||||||
// size * y + x
|
// size * y + x
|
||||||
display_item.position = positionable ? FONT.constants.SIZES.LINE * ((bits >> 5) & 0x001F) + (bits & 0x001F) : default_position;
|
display_item.position = positionable ? FONT.constants.SIZES.LINE * ((bits >> 5) & 0x001F) + (bits & 0x001F) : default_position;
|
||||||
|
|
||||||
display_item.isVisible = [];
|
display_item.isVisible = [];
|
||||||
for (let osd_profile = 0; osd_profile < OSD.getNumberOfProfiles(); osd_profile++) {
|
for (let osd_profile = 0; osd_profile < OSD.getNumberOfProfiles(); osd_profile++) {
|
||||||
display_item.isVisible[osd_profile] = (bits & (OSD.constants.VISIBLE << osd_profile)) != 0;
|
display_item.isVisible[osd_profile] = (bits & (OSD.constants.VISIBLE << osd_profile)) != 0;
|
||||||
|
@ -1740,7 +1740,7 @@ OSD.msp = {
|
||||||
result.push8(OSD.data.osd_profiles.selected + 1);
|
result.push8(OSD.data.osd_profiles.selected + 1);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
return result;
|
return result;
|
||||||
},
|
},
|
||||||
|
@ -1824,7 +1824,7 @@ OSD.msp = {
|
||||||
if (expectedStatsCount != OSD.constants.STATISTIC_FIELDS.length) {
|
if (expectedStatsCount != OSD.constants.STATISTIC_FIELDS.length) {
|
||||||
console.error("Firmware is transmitting a different number of statistics (" + expectedStatsCount + ") to what the configurator is expecting (" + OSD.constants.STATISTIC_FIELDS.length + ")");
|
console.error("Firmware is transmitting a different number of statistics (" + expectedStatsCount + ") to what the configurator is expecting (" + OSD.constants.STATISTIC_FIELDS.length + ")");
|
||||||
}
|
}
|
||||||
|
|
||||||
for (var i = 0; i < expectedStatsCount; i++) {
|
for (var i = 0; i < expectedStatsCount; i++) {
|
||||||
|
|
||||||
let v = view.readU8();
|
let v = view.readU8();
|
||||||
|
@ -2104,7 +2104,7 @@ TABS.osd.initialize = function (callback) {
|
||||||
$('.warnings-container div.cf_tip').attr('title', i18n.getMessage('osdSectionHelpWarnings'));
|
$('.warnings-container div.cf_tip').attr('title', i18n.getMessage('osdSectionHelpWarnings'));
|
||||||
|
|
||||||
function titleizeField(field) {
|
function titleizeField(field) {
|
||||||
let finalFieldName = null;
|
let finalFieldName = null;
|
||||||
if (field.text) {
|
if (field.text) {
|
||||||
if (Array.isArray(field.text) && i18n.existsMessage(field.text[0])) {
|
if (Array.isArray(field.text) && i18n.existsMessage(field.text[0])) {
|
||||||
finalFieldName = i18n.getMessage(field.text[0], field.text.slice(1));
|
finalFieldName = i18n.getMessage(field.text[0], field.text.slice(1));
|
||||||
|
@ -2467,7 +2467,7 @@ TABS.osd.initialize = function (callback) {
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
|
|
||||||
let finalFieldName = titleizeField(field);
|
let finalFieldName = titleizeField(field);
|
||||||
$field.append('<label for="' + field.name + '" class="char-label">' + finalFieldName + '</label>');
|
$field.append('<label for="' + field.name + '" class="char-label">' + finalFieldName + '</label>');
|
||||||
if (field.positionable && field.isVisible[OSD.getCurrentPreviewProfile()]) {
|
if (field.positionable && field.isVisible[OSD.getCurrentPreviewProfile()]) {
|
||||||
$field.append(
|
$field.append(
|
||||||
|
@ -2542,7 +2542,7 @@ TABS.osd.initialize = function (callback) {
|
||||||
for (var i = 0; i < arrayElements.length; i++) {
|
for (var i = 0; i < arrayElements.length; i++) {
|
||||||
var element = arrayElements[i];
|
var element = arrayElements[i];
|
||||||
//Add string to the preview.
|
//Add string to the preview.
|
||||||
if (element.constructor === String) {
|
if (element.constructor === String) {
|
||||||
for(var j = 0; j < element.length; j++) {
|
for(var j = 0; j < element.length; j++) {
|
||||||
var charCode = element.charCodeAt(j);
|
var charCode = element.charCodeAt(j);
|
||||||
OSD.drawByOrder(selectedPosition++, field, charCode, j, i);
|
OSD.drawByOrder(selectedPosition++, field, charCode, j, i);
|
||||||
|
|
|
@ -28,17 +28,17 @@ TABS.servos.initialize = function (callback) {
|
||||||
$('#content').load("./tabs/servos.html", process_html);
|
$('#content').load("./tabs/servos.html", process_html);
|
||||||
}
|
}
|
||||||
get_servo_configurations();
|
get_servo_configurations();
|
||||||
|
|
||||||
function update_ui() {
|
function update_ui() {
|
||||||
|
|
||||||
if (semver.lt(CONFIG.apiVersion, "1.12.0") || SERVO_CONFIG.length == 0) {
|
if (semver.lt(CONFIG.apiVersion, "1.12.0") || SERVO_CONFIG.length == 0) {
|
||||||
|
|
||||||
$(".tab-servos").removeClass("supported");
|
$(".tab-servos").removeClass("supported");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
$(".tab-servos").addClass("supported");
|
$(".tab-servos").addClass("supported");
|
||||||
|
|
||||||
var servoCheckbox = '';
|
var servoCheckbox = '';
|
||||||
var servoHeader = '';
|
var servoHeader = '';
|
||||||
for (var i = 0; i < RC.active_channels-4; i++) {
|
for (var i = 0; i < RC.active_channels-4; i++) {
|
||||||
|
@ -57,9 +57,9 @@ TABS.servos.initialize = function (callback) {
|
||||||
$('div.tab-servos table.fields tr.main').append(servoHeader);
|
$('div.tab-servos table.fields tr.main').append(servoHeader);
|
||||||
|
|
||||||
function process_servos(name, alternate, obj) {
|
function process_servos(name, alternate, obj) {
|
||||||
|
|
||||||
$('div.supported_wrapper').show();
|
$('div.supported_wrapper').show();
|
||||||
|
|
||||||
$('div.tab-servos table.fields').append('\
|
$('div.tab-servos table.fields').append('\
|
||||||
<tr> \
|
<tr> \
|
||||||
<td style="text-align: center">' + name + '</td>\
|
<td style="text-align: center">' + name + '</td>\
|
||||||
|
@ -91,9 +91,9 @@ TABS.servos.initialize = function (callback) {
|
||||||
select.val(SERVO_CONFIG[obj].rate);
|
select.val(SERVO_CONFIG[obj].rate);
|
||||||
|
|
||||||
$('div.tab-servos table.fields tr:last').data('info', {'obj': obj});
|
$('div.tab-servos table.fields tr:last').data('info', {'obj': obj});
|
||||||
|
|
||||||
// UI hooks
|
// UI hooks
|
||||||
|
|
||||||
// only one checkbox for indicating a channel to forward can be selected at a time, perhaps a radio group would be best here.
|
// only one checkbox for indicating a channel to forward can be selected at a time, perhaps a radio group would be best here.
|
||||||
$('div.tab-servos table.fields tr:last td.channel input').click(function () {
|
$('div.tab-servos table.fields tr:last td.channel input').click(function () {
|
||||||
if($(this).is(':checked')) {
|
if($(this).is(':checked')) {
|
||||||
|
@ -112,10 +112,10 @@ TABS.servos.initialize = function (callback) {
|
||||||
if (channelIndex == -1) {
|
if (channelIndex == -1) {
|
||||||
channelIndex = undefined;
|
channelIndex = undefined;
|
||||||
}
|
}
|
||||||
|
|
||||||
SERVO_CONFIG[info.obj].indexOfChannelToForward = channelIndex;
|
SERVO_CONFIG[info.obj].indexOfChannelToForward = channelIndex;
|
||||||
|
|
||||||
|
|
||||||
SERVO_CONFIG[info.obj].middle = parseInt($('.middle input', this).val());
|
SERVO_CONFIG[info.obj].middle = parseInt($('.middle input', this).val());
|
||||||
SERVO_CONFIG[info.obj].min = parseInt($('.min input', this).val());
|
SERVO_CONFIG[info.obj].min = parseInt($('.min input', this).val());
|
||||||
SERVO_CONFIG[info.obj].max = parseInt($('.max input', this).val());
|
SERVO_CONFIG[info.obj].max = parseInt($('.max input', this).val());
|
||||||
|
@ -123,7 +123,7 @@ TABS.servos.initialize = function (callback) {
|
||||||
var val = parseInt($('.direction select', this).val());
|
var val = parseInt($('.direction select', this).val());
|
||||||
SERVO_CONFIG[info.obj].rate = val;
|
SERVO_CONFIG[info.obj].rate = val;
|
||||||
});
|
});
|
||||||
|
|
||||||
//
|
//
|
||||||
// send data to FC
|
// send data to FC
|
||||||
//
|
//
|
||||||
|
@ -132,7 +132,7 @@ TABS.servos.initialize = function (callback) {
|
||||||
function send_servo_mixer_rules() {
|
function send_servo_mixer_rules() {
|
||||||
mspHelper.sendServoConfigurations(save_to_eeprom);
|
mspHelper.sendServoConfigurations(save_to_eeprom);
|
||||||
}
|
}
|
||||||
|
|
||||||
function save_to_eeprom() {
|
function save_to_eeprom() {
|
||||||
if (save_configuration_to_eeprom) {
|
if (save_configuration_to_eeprom) {
|
||||||
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, function () {
|
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, function () {
|
||||||
|
@ -147,7 +147,7 @@ TABS.servos.initialize = function (callback) {
|
||||||
$('div.tab-servos table.fields tr:not(:first)').remove();
|
$('div.tab-servos table.fields tr:not(:first)').remove();
|
||||||
|
|
||||||
for (var servoIndex = 0; servoIndex < 8; servoIndex++) {
|
for (var servoIndex = 0; servoIndex < 8; servoIndex++) {
|
||||||
process_servos('Servo ' + servoIndex, '', servoIndex, false);
|
process_servos('Servo ' + servoIndex, '', servoIndex);
|
||||||
}
|
}
|
||||||
|
|
||||||
// UI hooks for dynamically generated elements
|
// UI hooks for dynamically generated elements
|
||||||
|
@ -157,20 +157,20 @@ TABS.servos.initialize = function (callback) {
|
||||||
GUI.timeout_add('servos_update', servos_update, 10);
|
GUI.timeout_add('servos_update', servos_update, 10);
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
|
|
||||||
$('a.update').click(function () {
|
$('a.update').click(function () {
|
||||||
servos_update(true);
|
servos_update(true);
|
||||||
});
|
});
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
function process_html() {
|
function process_html() {
|
||||||
|
|
||||||
update_ui();
|
update_ui();
|
||||||
|
|
||||||
// translate to user-selected language
|
// translate to user-selected language
|
||||||
i18n.localizePage();
|
i18n.localizePage();
|
||||||
|
|
||||||
// status data pulled via separate timer with static speed
|
// status data pulled via separate timer with static speed
|
||||||
GUI.interval_add('status_pull', function () {
|
GUI.interval_add('status_pull', function () {
|
||||||
MSP.send_message(MSPCodes.MSP_STATUS);
|
MSP.send_message(MSPCodes.MSP_STATUS);
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue