Update backup/restore functionality so that it restores adjustments,

auxiliary settings and channel forwarding (per-profile).  Add "Warning
Cell Voltage" to the UI.
10.3.x-maintenance
Dominic Clifton 2014-12-21 12:29:36 +00:00
parent e1d2fb3163
commit 502cf718ab
10 changed files with 139 additions and 87 deletions

View File

@ -402,6 +402,9 @@
"configurationBatteryMaximum": {
"message": "Maximum Cell Voltage"
},
"configurationBatteryWarning": {
"message": "Warning Cell Voltage"
},
"configurationBatteryScale": {
"message": "Voltage Scale"
},

View File

@ -10,11 +10,17 @@ function configuration_backup(callback) {
MSP_codes.MSP_PID,
MSP_codes.MSP_RC_TUNING,
MSP_codes.MSP_ACC_TRIM,
MSP_codes.MSP_SERVO_CONF
MSP_codes.MSP_SERVO_CONF,
MSP_codes.MSP_CHANNEL_FORWARDING,
MSP_codes.MSP_MODE_RANGES,
MSP_codes.MSP_ADJUSTMENT_RANGES
];
var uniqueData = [
// Not used by cleanflight, and it's wrong anyway - AUX settings are per-profile in baseflight.
/*
MSP_codes.MSP_BOX,
*/
MSP_codes.MSP_MISC,
MSP_codes.MSP_RCMAP,
MSP_codes.MSP_CONFIG
@ -54,7 +60,9 @@ function configuration_backup(callback) {
'PID': jQuery.extend(true, [], PIDs),
'RC': jQuery.extend(true, {}, RC_tuning),
'AccTrim': jQuery.extend(true, [], CONFIG.accelerometerTrims),
'ServoConfig': jQuery.extend(true, [], SERVO_CONFIG)
'ServoConfig': jQuery.extend(true, [], SERVO_CONFIG),
'ModeRanges': jQuery.extend(true, [], MODE_RANGES),
'AdjustmentRanges': jQuery.extend(true, [], ADJUSTMENT_RANGES)
});
codeKey = 0;
@ -82,7 +90,10 @@ function configuration_backup(callback) {
query();
});
} else {
// Not used by cleanflight, and it's wrong anyway - AUX settings are per-profile in baseflight.
/*
configuration.AUX = jQuery.extend(true, [], AUX_CONFIG_values);
*/
configuration.MISC = jQuery.extend(true, {}, MISC);
configuration.RCMAP = jQuery.extend(true, [], RC_MAP);
configuration.BF_CONFIG = jQuery.extend(true, {}, BF_CONFIG);
@ -107,7 +118,7 @@ function configuration_backup(callback) {
now = (d.getMonth() + 1) + '.' + d.getDate() + '.' + d.getFullYear() + '.' + d.getHours() + '.' + d.getMinutes();
// create or load the file
chrome.fileSystem.chooseEntry({type: 'saveFile', suggestedName: 'baseflight_backup_' + now, accepts: accepts}, function (fileEntry) {
chrome.fileSystem.chooseEntry({type: 'saveFile', suggestedName: 'cleanflight_backup_' + now, accepts: accepts}, function (fileEntry) {
if (chrome.runtime.lastError) {
console.error(chrome.runtime.lastError.message);
return;
@ -263,11 +274,15 @@ function configuration_restore(callback) {
MSP_codes.MSP_SET_PID,
MSP_codes.MSP_SET_RC_TUNING,
MSP_codes.MSP_SET_ACC_TRIM,
MSP_codes.MSP_SET_SERVO_CONF
MSP_codes.MSP_SET_SERVO_CONF,
MSP_codes.MSP_SET_CHANNEL_FORWARDING
];
var uniqueData = [
// Not used by cleanflight, and it's wrong anyway - AUX settings are per-profile in baseflight.
/*
MSP_codes.MSP_SET_BOX,
*/
MSP_codes.MSP_SET_MISC,
MSP_codes.MSP_SET_RCMAP,
MSP_codes.MSP_SET_CONFIG
@ -295,14 +310,16 @@ function configuration_restore(callback) {
RC_tuning = configuration.profiles[profile].RC;
CONFIG.accelerometerTrims = configuration.profiles[profile].AccTrim;
SERVO_CONFIG = configuration.profiles[profile].ServoConfig;
MODE_RANGES = configuration.profiles[profile].ModeRanges;
ADJUSTMENT_RANGES = configuration.profiles[profile].AdjustmentRanges;
}
function query() {
function upload_using_specific_commands() {
MSP.send_message(profileSpecificData[codeKey], MSP.crunch(profileSpecificData[codeKey]), false, function () {
codeKey++;
if (codeKey < profileSpecificData.length) {
query();
upload_using_specific_commands();
} else {
codeKey = 0;
savingProfile++;
@ -311,7 +328,7 @@ function configuration_restore(callback) {
load_objects(savingProfile);
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () {
MSP.send_message(MSP_codes.MSP_SELECT_SETTING, [savingProfile], false, query);
MSP.send_message(MSP_codes.MSP_SELECT_SETTING, [savingProfile], false, upload_using_specific_commands);
});
} else {
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () {
@ -322,16 +339,26 @@ function configuration_restore(callback) {
});
}
function upload_mode_ranges() {
MSP.sendModeRanges(upload_adjustment_ranges);
}
function upload_adjustment_ranges() {
MSP.sendAdjustmentRanges(upload_using_specific_commands);
}
// start uploading
load_objects(0);
query();
upload_mode_ranges();
}
function upload_unique_data() {
var codeKey = 0;
function load_objects() {
// Disabled, cleanflight does not use MSP_BOX.
/*
AUX_CONFIG_values = configuration.AUX;
*/
MISC = configuration.MISC;
RC_MAP = configuration.RCMAP;
BF_CONFIG = configuration.BF_CONFIG;

View File

@ -65,7 +65,10 @@ var RC_tuning = {
var AUX_CONFIG = [];
var AUX_CONFIG_IDS = [];
//Disabled, cleanflight does not use MSP_BOX.
/*
var AUX_CONFIG_values = [];
*/
var MODE_RANGES = [];
var ADJUSTMENT_RANGES = [];
@ -126,5 +129,5 @@ var MISC = {
vbatscale: 0,
vbatmincellvoltage: 0,
vbatmaxcellvoltage: 0,
placeholder3: 0
vbatwarningcellvoltage: 0
};

View File

@ -292,6 +292,7 @@ var MSP = {
}
}
break;
// Disabled, cleanflight does not use MSP_BOX.
/*
case MSP_codes.MSP_BOX:
AUX_CONFIG_values = []; // empty the array as new data is coming in
@ -318,7 +319,7 @@ var MSP = {
MISC.vbatscale = data.getUint8(18, 1); // 10-200
MISC.vbatmincellvoltage = data.getUint8(19, 1) / 10; // 10-50
MISC.vbatmaxcellvoltage = data.getUint8(20, 1) / 10; // 10-50
MISC.placeholder3 = data.getUint8(21, 1);
MISC.vbatwarningcellvoltage = data.getUint8(21, 1) / 10; // 10-50
break;
case MSP_codes.MSP_MOTOR_PINS:
console.log(data);
@ -724,12 +725,15 @@ MSP.crunch = function (code) {
buffer.push(parseInt(RC_tuning.throttle_MID * 100));
buffer.push(parseInt(RC_tuning.throttle_EXPO * 100));
break;
// Disabled, cleanflight does not use MSP_SET_BOX.
/*
case MSP_codes.MSP_SET_BOX:
for (var i = 0; i < AUX_CONFIG_values.length; i++) {
buffer.push(lowByte(AUX_CONFIG_values[i]));
buffer.push(highByte(AUX_CONFIG_values[i]));
}
break;
*/
case MSP_codes.MSP_SET_RCMAP:
for (var i = 0; i < RC_MAP.length; i++) {
buffer.push(RC_MAP[i]);
@ -763,7 +767,7 @@ MSP.crunch = function (code) {
buffer.push(MISC.vbatscale);
buffer.push(MISC.vbatmincellvoltage * 10);
buffer.push(MISC.vbatmaxcellvoltage * 10);
buffer.push(MISC.placeholder3);
buffer.push(MISC.vbatwarningcellvoltage * 10);
break;
case MSP_codes.MSP_SET_SERVO_CONF:
for (var i = 0; i < SERVO_CONFIG.length; i++) {
@ -779,10 +783,77 @@ MSP.crunch = function (code) {
buffer.push(lowByte(SERVO_CONFIG[i].rate));
}
break;
case MSP_codes.MSP_SET_CHANNEL_FORWARDING:
for (var i = 0; i < SERVO_CONFIG.length; i++) {
buffer.push(SERVO_CONFIG[i].indexOfChannelToForward);
}
break;
default:
return false;
}
return buffer;
};
};
MSP.sendModeRanges = function(onCompleteCallback) {
var nextFunction = send_next_mode_range;
var modeRangeIndex = 0;
send_next_mode_range();
function send_next_mode_range() {
var modeRange = MODE_RANGES[modeRangeIndex];
var AUX_val_buffer_out = [];
AUX_val_buffer_out.push(modeRangeIndex);
AUX_val_buffer_out.push(modeRange.id);
AUX_val_buffer_out.push(modeRange.auxChannelIndex);
AUX_val_buffer_out.push((modeRange.range.start - 900) / 25);
AUX_val_buffer_out.push((modeRange.range.end - 900) / 25);
// prepare for next iteration
modeRangeIndex++;
if (modeRangeIndex == MODE_RANGES.length) {
nextFunction = onCompleteCallback;
}
MSP.send_message(MSP_codes.MSP_SET_MODE_RANGE, AUX_val_buffer_out, false, nextFunction);
}
};
MSP.sendAdjustmentRanges = function(onCompleteCallback) {
var nextFunction = send_next_adjustment_range;
var adjustmentRangeIndex = 0;
send_next_adjustment_range();
function send_next_adjustment_range() {
var adjustmentRange = ADJUSTMENT_RANGES[adjustmentRangeIndex];
var ADJUSTMENT_val_buffer_out = [];
ADJUSTMENT_val_buffer_out.push(adjustmentRangeIndex);
ADJUSTMENT_val_buffer_out.push(adjustmentRange.slotIndex);
ADJUSTMENT_val_buffer_out.push(adjustmentRange.auxChannelIndex);
ADJUSTMENT_val_buffer_out.push((adjustmentRange.range.start - 900) / 25);
ADJUSTMENT_val_buffer_out.push((adjustmentRange.range.end - 900) / 25);
ADJUSTMENT_val_buffer_out.push(adjustmentRange.adjustmentFunction);
ADJUSTMENT_val_buffer_out.push(adjustmentRange.auxSwitchChannelIndex);
// prepare for next iteration
adjustmentRangeIndex++;
if (adjustmentRangeIndex == ADJUSTMENT_RANGES.length) {
nextFunction = onCompleteCallback;
}
MSP.send_message(MSP_codes.MSP_SET_ADJUSTMENT_RANGE, ADJUSTMENT_val_buffer_out, false, nextFunction);
}
};

View File

@ -180,7 +180,7 @@ TABS.adjustments.initialize = function (callback) {
auxSwitchChannelIndex: 0
};
$('.adjustments .adjustment').each(function () {
$('.tab-adjustments .adjustments .adjustment').each(function () {
var adjustmentElement = $(this);
if ($(adjustmentElement).find('.enable').prop("checked")) {
@ -208,36 +208,8 @@ TABS.adjustments.initialize = function (callback) {
//
// send data to FC
//
var nextFunction = send_next_adjustment_range;
var adjustmentRangeIndex = 0;
send_next_adjustment_range();
MSP.sendAdjustmentRanges(save_to_eeprom);
function send_next_adjustment_range() {
var adjustmentRange = ADJUSTMENT_RANGES[adjustmentRangeIndex];
var ADJUSTMENT_val_buffer_out = [];
ADJUSTMENT_val_buffer_out.push(adjustmentRangeIndex);
ADJUSTMENT_val_buffer_out.push(adjustmentRange.slotIndex);
ADJUSTMENT_val_buffer_out.push(adjustmentRange.auxChannelIndex);
ADJUSTMENT_val_buffer_out.push((adjustmentRange.range.start - 900) / 25);
ADJUSTMENT_val_buffer_out.push((adjustmentRange.range.end - 900) / 25);
ADJUSTMENT_val_buffer_out.push(adjustmentRange.adjustmentFunction);
ADJUSTMENT_val_buffer_out.push(adjustmentRange.auxSwitchChannelIndex);
// prepare for next iteration
adjustmentRangeIndex++;
if (adjustmentRangeIndex == requiredAdjustmentRangeCount) {
nextFunction = save_to_eeprom;
}
MSP.send_message(MSP_codes.MSP_SET_ADJUSTMENT_RANGE, ADJUSTMENT_val_buffer_out, false, nextFunction);
}
function save_to_eeprom() {
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () {
GUI.log(chrome.i18n.getMessage('adjustmentsEepromSaved'));

View File

@ -178,7 +178,7 @@ TABS.auxiliary.initialize = function (callback) {
MODE_RANGES = [];
$('.modes .mode').each(function () {
$('.tab-auxiliary .modes .mode').each(function () {
var modeElement = $(this);
var modeId = modeElement.data('id');
@ -212,33 +212,7 @@ TABS.auxiliary.initialize = function (callback) {
//
// send data to FC
//
var nextFunction = send_next_mode_range;
var modeRangeIndex = 0;
send_next_mode_range();
function send_next_mode_range() {
var modeRange = MODE_RANGES[modeRangeIndex];
var AUX_val_buffer_out = [];
AUX_val_buffer_out.push(modeRangeIndex);
AUX_val_buffer_out.push(modeRange.id);
AUX_val_buffer_out.push(modeRange.auxChannelIndex);
AUX_val_buffer_out.push((modeRange.range.start - 900) / 25);
AUX_val_buffer_out.push((modeRange.range.end - 900) / 25);
// prepare for next iteration
modeRangeIndex++;
if (modeRangeIndex == requiredModesRangeCount) {
nextFunction = save_to_eeprom;
}
MSP.send_message(MSP_codes.MSP_SET_MODE_RANGE, AUX_val_buffer_out, false, nextFunction);
}
MSP.sendModeRanges(save_to_eeprom);
function save_to_eeprom() {
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () {

View File

@ -121,6 +121,12 @@
<span i18n="configurationBatteryMaximum"></span>
</label>
</div>
<div class="number">
<label>
<input type="number" name="warningcellvoltage" step="0.1" min="1" max="5" />
<span i18n="configurationBatteryWarning"></span>
</label>
</div>
<div class="number">
<label>
<input type="number" name="voltagescale" step="1" min="10" max="200" />

View File

@ -190,6 +190,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
// fill battery
$('input[name="mincellvoltage"]').val(MISC.vbatmincellvoltage);
$('input[name="maxcellvoltage"]').val(MISC.vbatmaxcellvoltage);
$('input[name="warningcellvoltage"]').val(MISC.vbatwarningcellvoltage);
$('input[name="voltagescale"]').val(MISC.vbatscale);
// fill current
@ -229,6 +230,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
MISC.vbatmincellvoltage = parseFloat($('input[name="mincellvoltage"]').val());
MISC.vbatmaxcellvoltage = parseFloat($('input[name="maxcellvoltage"]').val());
MISC.vbatwarningcellvoltage = parseFloat($('input[name="warningcellvoltage"]').val());
MISC.vbatscale = parseInt($('input[name="voltagescale"]').val());
BF_CONFIG.currentscale = parseInt($('input[name="currentscale"]').val());

View File

@ -1,3 +1,5 @@
// Disabled via main.js/main.html, cleanflight does not use MSP_BOX.
'use strict';
TABS.modes = {};

View File

@ -163,25 +163,17 @@ TABS.servos.initialize = function (callback) {
}
});
// send channel forwarding over to mcu
var buffer_out = [];
var needle = 0;
for (var i = 0; i < SERVO_CONFIG.length; i++) {
buffer_out[needle++] = SERVO_CONFIG[i].indexOfChannelToForward;
}
MSP.send_message(MSP_codes.MSP_SET_CHANNEL_FORWARDING, buffer_out);
MSP.send_message(MSP_codes.MSP_SET_SERVO_CONF, MSP.crunch(MSP_codes.MSP_SET_SERVO_CONF), false, function () {
if (save_to_eeprom) {
// Save changes to EEPROM
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () {
GUI.log(chrome.i18n.getMessage('servosEepromSave'));
});
}
MSP.send_message(MSP_codes.MSP_SET_CHANNEL_FORWARDING, MSP.crunch(MSP_codes.MSP_SET_CHANNEL_FORWARDING), false, function () {
MSP.send_message(MSP_codes.MSP_SET_SERVO_CONF, MSP.crunch(MSP_codes.MSP_SET_SERVO_CONF), false, function () {
if (save_to_eeprom) {
// Save changes to EEPROM
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () {
GUI.log(chrome.i18n.getMessage('servosEepromSave'));
});
}
});
});
}
// drop previous table