1
0
Fork 0
mirror of https://github.com/betaflight/betaflight-configurator.git synced 2025-07-26 01:35:28 +03:00

Merge branch 'development' into thenickdude-private-development

Conflicts:
	js/msp.js
This commit is contained in:
Dominic Clifton 2015-12-18 01:56:57 +01:00
commit 251712c85d
11 changed files with 165 additions and 70 deletions

View file

@ -984,6 +984,12 @@
"cliInputPlaceholder": { "cliInputPlaceholder": {
"message": "Write your command here" "message": "Write your command here"
}, },
"cliEnter": {
"message": "CLI mode detected"
},
"cliReboot": {
"message": "CLI reboot detected"
},
"loggingNote": { "loggingNote": {
"message": "Data will be logged in this tab <span style=\"color: red\">only</span>, leaving the tab will <span style=\"color: red\">cancel</span> logging and application will return to its normal <strong>\"configurator\"</strong> state.<br /> You are free to select the global update period, data will be written into the log file every <strong>1</strong> second for performance reasons." "message": "Data will be logged in this tab <span style=\"color: red\">only</span>, leaving the tab will <span style=\"color: red\">cancel</span> logging and application will return to its normal <strong>\"configurator\"</strong> state.<br /> You are free to select the global update period, data will be written into the log file every <strong>1</strong> second for performance reasons."

View file

@ -676,7 +676,6 @@ function configuration_restore(callback) {
if (semver.gte(CONFIG.apiVersion, "1.15.0")) { if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
uniqueData.push(MSP_codes.MSP_SET_RX_CONFIG); uniqueData.push(MSP_codes.MSP_SET_RX_CONFIG);
uniqueData.push(MSP_codes.MSP_SET_FAILSAFE_CONFIG); uniqueData.push(MSP_codes.MSP_SET_FAILSAFE_CONFIG);
uniqueData.push(MSP_codes.MSP_SET_RXFAIL_CONFIG);
} }
} }
@ -701,7 +700,7 @@ function configuration_restore(callback) {
send_unique_data_item(); send_unique_data_item();
}); });
} else { } else {
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, send_led_strip_config); send_led_strip_config();
} }
} }
@ -714,9 +713,21 @@ function configuration_restore(callback) {
} }
function send_led_strip_config() { function send_led_strip_config() {
MSP.sendLedStripConfig(reboot); MSP.sendLedStripConfig(send_rxfail_config);
} }
function send_rxfail_config() {
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
MSP.sendRxFailConfig(save_to_eeprom);
} else {
save_to_eeprom();
}
}
function save_to_eeprom() {
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, reboot);
}
function reboot() { function reboot() {
GUI.log(chrome.i18n.getMessage('eeprom_saved_ok')); GUI.log(chrome.i18n.getMessage('eeprom_saved_ok'));

View file

@ -803,12 +803,14 @@ var MSP = {
offset++; offset++;
FAILSAFE_CONFIG.failsafe_throttle = data.getUint16(offset, 1); FAILSAFE_CONFIG.failsafe_throttle = data.getUint16(offset, 1);
offset += 2; offset += 2;
FAILSAFE_CONFIG.failsafe_kill_switch = data.getUint8(offset, 1); if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
offset++; FAILSAFE_CONFIG.failsafe_kill_switch = data.getUint8(offset, 1);
FAILSAFE_CONFIG.failsafe_throttle_low_delay = data.getUint16(offset, 1); offset++;
offset += 2; FAILSAFE_CONFIG.failsafe_throttle_low_delay = data.getUint16(offset, 1);
FAILSAFE_CONFIG.failsafe_procedure = data.getUint8(offset, 1); offset += 2;
offset++; FAILSAFE_CONFIG.failsafe_procedure = data.getUint8(offset, 1);
offset++;
}
break; break;
case MSP_codes.MSP_RXFAIL_CONFIG: case MSP_codes.MSP_RXFAIL_CONFIG:
@ -1203,17 +1205,11 @@ MSP.crunch = function (code) {
buffer.push(FAILSAFE_CONFIG.failsafe_off_delay); buffer.push(FAILSAFE_CONFIG.failsafe_off_delay);
buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_throttle)); buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_throttle));
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_throttle)); buffer.push(highByte(FAILSAFE_CONFIG.failsafe_throttle));
buffer.push(FAILSAFE_CONFIG.failsafe_kill_switch); if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_throttle_low_delay)); buffer.push(FAILSAFE_CONFIG.failsafe_kill_switch);
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_throttle_low_delay)); buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_throttle_low_delay));
buffer.push(FAILSAFE_CONFIG.failsafe_procedure); buffer.push(highByte(FAILSAFE_CONFIG.failsafe_throttle_low_delay));
break; buffer.push(FAILSAFE_CONFIG.failsafe_procedure);
case MSP_codes.MSP_SET_RXFAIL_CONFIG:
for (var i = 0; i < RXFAIL_CONFIG.length; i++) {
buffer.push(RXFAIL_CONFIG[i].mode);
buffer.push(lowByte(RXFAIL_CONFIG[i].value));
buffer.push(highByte(RXFAIL_CONFIG[i].value));
} }
break; break;
@ -1350,10 +1346,10 @@ MSP.sendServoConfigurations = function(onCompleteCallback) {
if (SERVO_CONFIG.length == 0) { if (SERVO_CONFIG.length == 0) {
onCompleteCallback(); onCompleteCallback();
} else {
nextFunction();
} }
nextFunction();
function send_next_servo_configuration() { function send_next_servo_configuration() {
var buffer = []; var buffer = [];
@ -1440,11 +1436,10 @@ MSP.sendModeRanges = function(onCompleteCallback) {
if (MODE_RANGES.length == 0) { if (MODE_RANGES.length == 0) {
onCompleteCallback(); onCompleteCallback();
} else {
send_next_mode_range();
} }
send_next_mode_range();
function send_next_mode_range() { function send_next_mode_range() {
var modeRange = MODE_RANGES[modeRangeIndex]; var modeRange = MODE_RANGES[modeRangeIndex];
@ -1473,11 +1468,10 @@ MSP.sendAdjustmentRanges = function(onCompleteCallback) {
if (ADJUSTMENT_RANGES.length == 0) { if (ADJUSTMENT_RANGES.length == 0) {
onCompleteCallback(); onCompleteCallback();
} else {
send_next_adjustment_range();
} }
send_next_adjustment_range();
function send_next_adjustment_range() { function send_next_adjustment_range() {
var adjustmentRange = ADJUSTMENT_RANGES[adjustmentRangeIndex]; var adjustmentRange = ADJUSTMENT_RANGES[adjustmentRangeIndex];
@ -1509,9 +1503,9 @@ MSP.sendLedStripConfig = function(onCompleteCallback) {
if (LED_STRIP.length == 0) { if (LED_STRIP.length == 0) {
onCompleteCallback(); onCompleteCallback();
} else {
send_next_led_strip_config();
} }
send_next_led_strip_config();
function send_next_led_strip_config() { function send_next_led_strip_config() {
@ -1579,8 +1573,41 @@ MSP.serialPortFunctionsToMask = function(functions) {
return mask; return mask;
} }
MSP.sendRxFailConfig = function(onCompleteCallback) {
var nextFunction = send_next_rxfail_config;
var rxFailIndex = 0;
if (RXFAIL_CONFIG.length == 0) {
onCompleteCallback();
} else {
send_next_rxfail_config();
}
function send_next_rxfail_config() {
var rxFail = RXFAIL_CONFIG[rxFailIndex];
var buffer = [];
buffer.push(rxFailIndex);
buffer.push(rxFail.mode);
buffer.push(lowByte(rxFail.value));
buffer.push(highByte(rxFail.value));
// prepare for next iteration
rxFailIndex++;
if (rxFailIndex == RXFAIL_CONFIG.length) {
nextFunction = onCompleteCallback;
}
MSP.send_message(MSP_codes.MSP_SET_RXFAIL_CONFIG, buffer, false, nextFunction);
}
};
MSP.SDCARD_STATE_NOT_PRESENT = 0; MSP.SDCARD_STATE_NOT_PRESENT = 0;
MSP.SDCARD_STATE_FATAL = 1; MSP.SDCARD_STATE_FATAL = 1;
MSP.SDCARD_STATE_CARD_INIT = 2; MSP.SDCARD_STATE_CARD_INIT = 2;
MSP.SDCARD_STATE_FS_INIT = 3; MSP.SDCARD_STATE_FS_INIT = 3;
MSP.SDCARD_STATE_READY = 4; MSP.SDCARD_STATE_READY = 4;

View file

@ -68,6 +68,12 @@ var serial = {
}); });
} }
break; break;
case 'break':
// This occurs on F1 boards with old firmware.
if (GUI.connected_to || GUI.connecting_to) {
$('a.connect').click();
}
break;
case 'timeout': case 'timeout':
// TODO // TODO
break; break;

View file

@ -2,6 +2,7 @@
TABS.cli = { TABS.cli = {
'validateText': "", 'validateText': "",
'currentLine': "",
'sequenceElements': 0 'sequenceElements': 0
}; };
@ -12,21 +13,13 @@ TABS.cli.initialize = function (callback) {
GUI.active_tab = 'cli'; GUI.active_tab = 'cli';
googleAnalytics.sendAppView('CLI'); googleAnalytics.sendAppView('CLI');
} }
$('#content').load("./tabs/cli.html", function () { $('#content').load("./tabs/cli.html", function () {
// translate to user-selected language // translate to user-selected language
localize(); localize();
CONFIGURATOR.cliActive = true; CONFIGURATOR.cliActive = true;
// Enter CLI mode
var bufferOut = new ArrayBuffer(1);
var bufView = new Uint8Array(bufferOut);
bufView[0] = 0x23; // #
serial.send(bufferOut);
var textarea = $('.tab-cli textarea'); var textarea = $('.tab-cli textarea');
textarea.keypress(function (event) { textarea.keypress(function (event) {
@ -62,6 +55,16 @@ TABS.cli.initialize = function (callback) {
// give input element user focus // give input element user focus
textarea.focus(); textarea.focus();
GUI.timeout_add('enter_cli', function enter_cli() {
// Enter CLI mode
var bufferOut = new ArrayBuffer(1);
var bufView = new Uint8Array(bufferOut);
bufView[0] = 0x23; // #
serial.send(bufferOut);
}, 250);
GUI.content_ready(callback); GUI.content_ready(callback);
}); });
}; };
@ -135,11 +138,13 @@ TABS.cli.read = function (readInfo) {
if (GUI.operating_system != "MacOS") { if (GUI.operating_system != "MacOS") {
text += "<br />"; text += "<br />";
} }
this.currentLine = "";
break; break;
case 13: // carriage return case 13: // carriage return
if (GUI.operating_system == "MacOS") { if (GUI.operating_system == "MacOS") {
text += "<br />"; text += "<br />";
} }
this.currentLine = "";
break; break;
case 60: case 60:
text += '&lt'; text += '&lt';
@ -150,19 +155,41 @@ TABS.cli.read = function (readInfo) {
default: default:
text += String.fromCharCode(data[i]); text += String.fromCharCode(data[i]);
this.currentLine += String.fromCharCode(data[i]);
}
}
if (this.currentLine == 'Rebooting') {
CONFIGURATOR.cliActive = false;
CONFIGURATOR.cliValid = false;
GUI.log(chrome.i18n.getMessage('cliReboot'));
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
if (BOARD.find_board_definition(CONFIG.boardIdentifier).vcp) { // VCP-based flight controls may crash old drivers, we catch and reconnect
$('a.connect').click();
GUI.timeout_add('start_connection',function start_connection() {
$('a.connect').click();
},2500);
} else {
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() {
MSP.send_message(MSP_codes.MSP_IDENT, false, false, function () {
GUI.log(chrome.i18n.getMessage('deviceReady'));
$('#tabs ul.mode-connected .tab_setup a').click();
});
},1500); // 1500 ms seems to be just the right amount of delay to prevent data request timeouts
} }
} }
} else { } else {
// try to catch part of valid CLI enter message // try to catch part of valid CLI enter message
this.validateText += String.fromCharCode(data[i]); this.validateText += String.fromCharCode(data[i]);
text += String.fromCharCode(data[i]);
} }
} }
if (!CONFIGURATOR.cliValid && this.validateText.indexOf('CLI') != -1) { if (!CONFIGURATOR.cliValid && this.validateText.indexOf('CLI') != -1) {
GUI.log(chrome.i18n.getMessage('cliEnter'));
CONFIGURATOR.cliValid = true; CONFIGURATOR.cliValid = true;
this.validateText = ""; this.validateText = "";
text = "Entering CLI Mode, type 'exit' to return, or 'help'<br /><br /># ";
} }
$('.tab-cli .window .wrapper').append(text); $('.tab-cli .window .wrapper').append(text);
@ -170,7 +197,7 @@ TABS.cli.read = function (readInfo) {
}; };
TABS.cli.cleanup = function (callback) { TABS.cli.cleanup = function (callback) {
if (!CONFIGURATOR.connectionValid) { if (!CONFIGURATOR.connectionValid || !CONFIGURATOR.cliValid) {
if (callback) callback(); if (callback) callback();
return; return;
} }
@ -190,10 +217,7 @@ TABS.cli.cleanup = function (callback) {
// we can setup an interval asking for data lets say every 200ms, when data arrives, callback will be triggered and tab switched // we can setup an interval asking for data lets say every 200ms, when data arrives, callback will be triggered and tab switched
// we could probably implement this someday // we could probably implement this someday
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() { GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() {
CONFIGURATOR.cliActive = false;
CONFIGURATOR.cliValid = false;
if (callback) callback(); if (callback) callback();
}, 5000); // if we dont allow enough time to reboot, CRC of "first" command sent will fail, keep an eye for this one }, 1000); // if we dont allow enough time to reboot, CRC of "first" command sent will fail, keep an eye for this one
}); });
}; };

View file

@ -493,7 +493,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
$('a.connect').click(); $('a.connect').click();
GUI.timeout_add('start_connection',function start_connection() { GUI.timeout_add('start_connection',function start_connection() {
$('a.connect').click(); $('a.connect').click();
},2000); },2500);
} else { } else {
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() { GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() {

View file

@ -317,7 +317,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
} }
function save_rxfail_config() { function save_rxfail_config() {
MSP.send_message(MSP_codes.MSP_SET_RXFAIL_CONFIG, MSP.crunch(MSP_codes.MSP_SET_RXFAIL_CONFIG), false, save_bf_config); MSP.sendRxFailConfig(save_bf_config);
} }
function save_bf_config() { function save_bf_config() {
@ -349,7 +349,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
$('a.connect').click(); $('a.connect').click();
GUI.timeout_add('start_connection',function start_connection() { GUI.timeout_add('start_connection',function start_connection() {
$('a.connect').click(); $('a.connect').click();
},2000); },2500);
} else { } else {
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() { GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() {

View file

@ -53,7 +53,7 @@
<li><a href="http://www.scorpionsystem.com" title="www.scorpionsystem.com" target="_blank">Scorpion <li><a href="http://www.scorpionsystem.com" title="www.scorpionsystem.com" target="_blank">Scorpion
Power Systems</a></li> Power Systems</a></li>
<li><a href="http://www.multigp.com" title="www.multigp.com" target="_blank">MultiGP</a></li> <li><a href="http://www.multigp.com" title="www.multigp.com" target="_blank">MultiGP</a></li>
<li><a href="makeitbuildit.co.uk" title="makeitbuildit.co.uk" target="_blank">MakeItBuildIt</a></li> <li><a href="http://makeitbuildit.co.uk" title="makeitbuildit.co.uk" target="_blank">MakeItBuildIt</a></li>
</ul> </ul>
</div> </div>
</div> </div>
@ -69,4 +69,4 @@
</div> </div>
</div> </div>
</div> </div>
</div> </div>

View file

@ -118,7 +118,7 @@
</div> </div>
<div class="notice"> <div class="notice">
<p i18n="motorsNotice"></p> <p i18n="motorsNotice"></p>
<label><input id="motorsEnableTestMode" class="togglesmall" type="checkbox" /><span <label><input id="motorsEnableTestMode" type="checkbox" /><span
class="motorsEnableTestMode" i18n="motorsEnableControl"></span></label> class="motorsEnableTestMode" i18n="motorsEnableControl"></span></label>
</div> </div>
<div class="cler-both"></div> <div class="cler-both"></div>

View file

@ -1,10 +1,16 @@
'use strict'; 'use strict';
TABS.motors = {}; TABS.motors = {
allowTestMode: false,
feature3DEnabled: false,
feature3DSupported: false
};
TABS.motors.initialize = function (callback) { TABS.motors.initialize = function (callback) {
var self = this; var self = this;
self.armed = false; self.armed = false;
self.feature3DSupported = false;
self.allowTestMode = true;
if (GUI.active_tab != 'motors') { if (GUI.active_tab != 'motors') {
GUI.active_tab = 'motors'; GUI.active_tab = 'motors';
@ -20,13 +26,16 @@ TABS.motors.initialize = function (callback) {
} }
function load_3d() { function load_3d() {
MSP.send_message(MSP_codes.MSP_3D, false, false, get_motor_data); var next_callback = get_motor_data;
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
self.feature3DSupported = true;
MSP.send_message(MSP_codes.MSP_3D, false, false, next_callback);
} else {
next_callback();
}
} }
function update_arm_status() {
self.armed = bit_check(CONFIG.mode, 0);
}
function get_motor_data() { function get_motor_data() {
update_arm_status(); update_arm_status();
MSP.send_message(MSP_codes.MSP_MOTOR, false, false, load_html); MSP.send_message(MSP_codes.MSP_MOTOR, false, false, load_html);
@ -38,6 +47,10 @@ TABS.motors.initialize = function (callback) {
MSP.send_message(MSP_codes.MSP_MISC, false, false, get_arm_status); MSP.send_message(MSP_codes.MSP_MISC, false, false, get_arm_status);
function update_arm_status() {
self.armed = bit_check(CONFIG.mode, 0);
}
function initSensorData() { function initSensorData() {
for (var i = 0; i < 3; i++) { for (var i = 0; i < 3; i++) {
SENSOR_DATA.accelerometer[i] = 0; SENSOR_DATA.accelerometer[i] = 0;
@ -164,8 +177,14 @@ TABS.motors.initialize = function (callback) {
// translate to user-selected language // translate to user-selected language
localize(); localize();
$('#motorsEnableTestMode').prop('disabled', 'true'); self.feature3DEnabled = bit_check(BF_CONFIG.features, 12);
if (self.feature3DEnabled && !self.feature3DSupported) {
self.allowTestMode = false;
}
$('#motorsEnableTestMode').prop('disabled', 'true');
update_model(CONFIG.multiType); update_model(CONFIG.multiType);
// Always start with default/empty sensor data array, clean slate all // Always start with default/empty sensor data array, clean slate all
@ -296,12 +315,12 @@ TABS.motors.initialize = function (callback) {
$('div.sliders input').prop('min', MISC.mincommand); $('div.sliders input').prop('min', MISC.mincommand);
$('div.sliders input').prop('max', MISC.maxthrottle); $('div.sliders input').prop('max', MISC.maxthrottle);
$('div.values li:not(:last)').text(MISC.mincommand); $('div.values li:not(:last)').text(MISC.mincommand);
if(bit_check(BF_CONFIG.features,12)){ if(self.feature3DEnabled && self.feature3DSupported) {
$('div.sliders input').val(_3D.neutral3d); $('div.sliders input').val(_3D.neutral3d);
}else{ } else {
$('div.sliders input').val(MISC.mincommand); $('div.sliders input').val(MISC.mincommand);
} }
// UI hooks // UI hooks
var buffering_set_motor = [], var buffering_set_motor = [],
@ -354,10 +373,10 @@ TABS.motors.initialize = function (callback) {
$('div.sliders input').prop('disabled', true); $('div.sliders input').prop('disabled', true);
// change all values to default // change all values to default
if (! bit_check(BF_CONFIG.features,12)) { if (self.feature3DEnabled && self.feature3DSupported) {
$('div.sliders input').val(MISC.mincommand);
} else {
$('div.sliders input').val(_3D.neutral3d); $('div.sliders input').val(_3D.neutral3d);
} else {
$('div.sliders input').val(MISC.mincommand);
} }
// trigger change event so values are sent to mcu // trigger change event so values are sent to mcu
@ -439,7 +458,9 @@ TABS.motors.initialize = function (callback) {
$('#motorsEnableTestMode').prop('disabled', true); $('#motorsEnableTestMode').prop('disabled', true);
$('#motorsEnableTestMode').prop('checked', false); $('#motorsEnableTestMode').prop('checked', false);
} else { } else {
$('#motorsEnableTestMode').prop('disabled', false); if (self.allowTestMode) {
$('#motorsEnableTestMode').prop('disabled', false);
}
} }
if (previousArmState != self.armed) { if (previousArmState != self.armed) {

View file

@ -266,7 +266,7 @@ TABS.ports.initialize = function (callback, scrollPosition) {
$('a.connect').click(); $('a.connect').click();
GUI.timeout_add('start_connection',function start_connection() { GUI.timeout_add('start_connection',function start_connection() {
$('a.connect').click(); $('a.connect').click();
},2000); },2500);
} else { } else {
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() { GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() {
MSP.send_message(MSP_codes.MSP_IDENT, false, false, function () { MSP.send_message(MSP_codes.MSP_IDENT, false, false, function () {