update servo tab on configurator
1) work around 1.9.0 MSP buffer size bug. 2) support updated API for 1.12 (CF >= 1.10.0)10.3.x-maintenance
parent
c0138f5f82
commit
1cb64130cc
|
@ -30,12 +30,21 @@ 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_CHANNEL_FORWARDING,
|
||||
MSP_codes.MSP_SERVO_CONFIGURATIONS,
|
||||
MSP_codes.MSP_MODE_RANGES,
|
||||
MSP_codes.MSP_ADJUSTMENT_RANGES
|
||||
];
|
||||
|
||||
function update_profile_specific_data_list() {
|
||||
if (semver.lt(CONFIG.apiVersion, "1.12.0")) {
|
||||
profileSpecificData.push(MSP_codes.MSP_CHANNEL_FORWARDING);
|
||||
} else {
|
||||
profileSpecificData.push(MSP_codes.MSP_SERVO_RULES);
|
||||
}
|
||||
}
|
||||
|
||||
update_profile_specific_data_list();
|
||||
|
||||
function fetch_specific_data() {
|
||||
var fetchingProfile = 0,
|
||||
codeKey = 0;
|
||||
|
@ -54,6 +63,7 @@ function configuration_backup(callback) {
|
|||
'RC': jQuery.extend(true, {}, RC_tuning),
|
||||
'AccTrim': jQuery.extend(true, [], CONFIG.accelerometerTrims),
|
||||
'ServoConfig': jQuery.extend(true, [], SERVO_CONFIG),
|
||||
'ServoRules': jQuery.extend(true, [], SERVO_RULES),
|
||||
'ModeRanges': jQuery.extend(true, [], MODE_RANGES),
|
||||
'AdjustmentRanges': jQuery.extend(true, [], ADJUSTMENT_RANGES)
|
||||
});
|
||||
|
@ -428,6 +438,31 @@ function configuration_restore(callback) {
|
|||
}
|
||||
}
|
||||
|
||||
if (semver.lt(migratedVersion, '0.66.0')) {
|
||||
// api 1.12 updated servo configuration protocol and added servo mixer rules
|
||||
for (var profileIndex = 0; i < configuration.profiles.length; i++) {
|
||||
|
||||
if (semver.eq(configuration.apiVersion, '1.10.0')) {
|
||||
// drop two unused servo configurations
|
||||
while (configuration.profiles[profileIndex].ServoConfig.length > 8) {
|
||||
configuration.profiles[profileIndex].ServoConfig.pop();
|
||||
}
|
||||
}
|
||||
for (var i = 0; i < configuration.profiles[profileIndex].ServoConfig.length; i++) {
|
||||
var servoConfig = profiles[profileIndex].ServoConfig;
|
||||
servoConfig[i].angleAtMin = 90;
|
||||
servoConfig[i].angleAtMax = 90;
|
||||
servoConfig[i].reversedInputSources = 0;
|
||||
}
|
||||
|
||||
configuration.profiles[profileIndex].ServoRules = [];
|
||||
}
|
||||
|
||||
migratedVersion = '0.66.0';
|
||||
|
||||
appliedMigrationsCount++;
|
||||
}
|
||||
|
||||
if (appliedMigrationsCount > 0) {
|
||||
GUI.log(chrome.i18n.getMessage('configMigrationSuccessful', [appliedMigrationsCount]));
|
||||
}
|
||||
|
@ -444,9 +479,7 @@ function configuration_restore(callback) {
|
|||
MSP_codes.MSP_SET_PID_CONTROLLER,
|
||||
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_CHANNEL_FORWARDING
|
||||
MSP_codes.MSP_SET_ACC_TRIM
|
||||
];
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_STATUS, false, false, function () {
|
||||
|
@ -472,6 +505,7 @@ function configuration_restore(callback) {
|
|||
RC_tuning = configuration.profiles[profile].RC;
|
||||
CONFIG.accelerometerTrims = configuration.profiles[profile].AccTrim;
|
||||
SERVO_CONFIG = configuration.profiles[profile].ServoConfig;
|
||||
SERVO_RULES = configuration.profiles[profile].ServoRules;
|
||||
MODE_RANGES = configuration.profiles[profile].ModeRanges;
|
||||
ADJUSTMENT_RANGES = configuration.profiles[profile].AdjustmentRanges;
|
||||
}
|
||||
|
@ -501,6 +535,14 @@ function configuration_restore(callback) {
|
|||
});
|
||||
}
|
||||
|
||||
function upload_servo_mix_rules() {
|
||||
MSP.sendServoMixRules(upload_servo_configuration);
|
||||
}
|
||||
|
||||
function upload_servo_configuration() {
|
||||
MSP.sendServoConfigurations(upload_mode_ranges);
|
||||
}
|
||||
|
||||
function upload_mode_ranges() {
|
||||
MSP.sendModeRanges(upload_adjustment_ranges);
|
||||
}
|
||||
|
@ -510,7 +552,7 @@ function configuration_restore(callback) {
|
|||
}
|
||||
// start uploading
|
||||
load_objects(0);
|
||||
upload_mode_ranges();
|
||||
upload_servo_configuration();
|
||||
}
|
||||
|
||||
function upload_unique_data() {
|
||||
|
|
|
@ -86,6 +86,7 @@ var MODE_RANGES = [];
|
|||
var ADJUSTMENT_RANGES = [];
|
||||
|
||||
var SERVO_CONFIG = [];
|
||||
var SERVO_RULES = [];
|
||||
|
||||
var SERIAL_CONFIG = {
|
||||
ports: [],
|
||||
|
|
220
js/msp.js
220
js/msp.js
|
@ -51,7 +51,7 @@ var MSP_codes = {
|
|||
MSP_PIDNAMES: 117,
|
||||
MSP_WP: 118,
|
||||
MSP_BOXIDS: 119,
|
||||
MSP_SERVO_CONF: 120,
|
||||
MSP_SERVO_CONFIGURATIONS: 120,
|
||||
|
||||
MSP_SET_RAW_RC: 200,
|
||||
MSP_SET_RAW_GPS: 201,
|
||||
|
@ -65,10 +65,13 @@ var MSP_codes = {
|
|||
MSP_SET_WP: 209,
|
||||
MSP_SELECT_SETTING: 210,
|
||||
MSP_SET_HEAD: 211,
|
||||
MSP_SET_SERVO_CONF: 212,
|
||||
MSP_SET_SERVO_CONFIGURATION: 212,
|
||||
MSP_SET_MOTOR: 214,
|
||||
|
||||
// MSP_BIND: 240,
|
||||
|
||||
MSP_SERVO_MIX_RULES: 241,
|
||||
MSP_SET_SERVO_MIX_RULE: 242,
|
||||
|
||||
MSP_EEPROM_WRITE: 250,
|
||||
|
||||
|
@ -80,7 +83,7 @@ var MSP_codes = {
|
|||
MSP_ACC_TRIM: 240, // get acc angle trim values
|
||||
MSP_SET_ACC_TRIM: 239, // set acc angle trim values
|
||||
MSP_GPS_SV_INFO: 164, // get Signal Strength
|
||||
|
||||
|
||||
// Additional private MSP for baseflight configurator (yes thats us \o/)
|
||||
MSP_RX_MAP: 64, // get channel map (also returns number of channels total)
|
||||
MSP_SET_RX_MAP: 65, // set rc map, numchannels to set comes from MSP_RX_MAP
|
||||
|
@ -444,22 +447,48 @@ var MSP = {
|
|||
AUX_CONFIG_IDS.push(data.getUint8(i));
|
||||
}
|
||||
break;
|
||||
case MSP_codes.MSP_SERVO_CONF:
|
||||
case MSP_codes.MSP_SERVO_MIX_RULES:
|
||||
break;
|
||||
|
||||
case MSP_codes.MSP_SERVO_CONFIGURATIONS:
|
||||
SERVO_CONFIG = []; // empty the array as new data is coming in
|
||||
|
||||
if (data.byteLength % 13 == 0) {
|
||||
for (var i = 0; i < data.byteLength; i += 13) {
|
||||
var arr = {
|
||||
'min': data.getInt16(i, 1),
|
||||
'max': data.getInt16(i + 2, 1),
|
||||
'middle': data.getInt16(i + 4, 1),
|
||||
'rate': data.getInt8(i + 6),
|
||||
'angleAtMin': data.getInt8(i + 7),
|
||||
'angleAtMax': data.getInt8(i + 8),
|
||||
'reversedChannels': data.getInt32(i + 9)
|
||||
};
|
||||
|
||||
SERVO_CONFIG.push(arr);
|
||||
if (semver.gte(CONFIG.apiVersion, "1.12.0")) {
|
||||
if (data.byteLength % 14 == 0) {
|
||||
for (var i = 0; i < data.byteLength; i += 14) {
|
||||
var arr = {
|
||||
'min': data.getInt16(i + 0, 1),
|
||||
'max': data.getInt16(i + 2, 1),
|
||||
'middle': data.getInt16(i + 4, 1),
|
||||
'rate': data.getInt8(i + 6),
|
||||
'angleAtMin': data.getUint8(i + 7),
|
||||
'angleAtMax': data.getUint8(i + 8),
|
||||
'indexOfChannelToForward': data.getInt8(i + 9),
|
||||
'reversedInputSources': data.getUint32(i + 10)
|
||||
};
|
||||
|
||||
SERVO_CONFIG.push(arr);
|
||||
}
|
||||
}
|
||||
} else {
|
||||
if (data.byteLength % 7 == 0) {
|
||||
for (var i = 0; i < data.byteLength; i += 7) {
|
||||
var arr = {
|
||||
'min': data.getInt16(i + 0, 1),
|
||||
'max': data.getInt16(i + 2, 1),
|
||||
'middle': data.getInt16(i + 4, 1),
|
||||
'rate': data.getInt8(i + 6)
|
||||
};
|
||||
|
||||
SERVO_CONFIG.push(arr);
|
||||
}
|
||||
}
|
||||
|
||||
if (semver.eq(CONFIG.apiVersion, '1.10.0')) {
|
||||
// drop two unused servo configurations due to MSP rx buffer to small)
|
||||
while (SERVO_CONFIG.length > 8) {
|
||||
SERVO_CONFIG.pop();
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
@ -493,7 +522,7 @@ var MSP = {
|
|||
case MSP_codes.MSP_SELECT_SETTING:
|
||||
console.log('Profile selected');
|
||||
break;
|
||||
case MSP_codes.MSP_SET_SERVO_CONF:
|
||||
case MSP_codes.MSP_SET_SERVO_CONFIGURATION:
|
||||
console.log('Servo Configuration saved');
|
||||
break;
|
||||
case MSP_codes.MSP_EEPROM_WRITE:
|
||||
|
@ -1038,32 +1067,6 @@ MSP.crunch = function (code) {
|
|||
buffer.push(MISC.vbatmaxcellvoltage * 10);
|
||||
buffer.push(MISC.vbatwarningcellvoltage * 10);
|
||||
break;
|
||||
case MSP_codes.MSP_SET_SERVO_CONF:
|
||||
for (var i = 0; i < SERVO_CONFIG.length; i++) {
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].min));
|
||||
buffer.push(highByte(SERVO_CONFIG[i].min));
|
||||
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].max));
|
||||
buffer.push(highByte(SERVO_CONFIG[i].max));
|
||||
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].middle));
|
||||
buffer.push(highByte(SERVO_CONFIG[i].middle));
|
||||
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].rate));
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.11.0")) {
|
||||
buffer.push(SERVO_CONFIG[i].angleAtMin);
|
||||
buffer.push(SERVO_CONFIG[i].angleAtMax);
|
||||
}
|
||||
|
||||
if (semver.gte(CONFIG.apiVersion, "1.12.0")) {
|
||||
buffer.push(specificByte(SERVO_CONFIG[i].reversedChannels, 0));
|
||||
buffer.push(specificByte(SERVO_CONFIG[i].reversedChannels, 1));
|
||||
buffer.push(specificByte(SERVO_CONFIG[i].reversedChannels, 2));
|
||||
buffer.push(specificByte(SERVO_CONFIG[i].reversedChannels, 3));
|
||||
}
|
||||
}
|
||||
break;
|
||||
case MSP_codes.MSP_SET_CHANNEL_FORWARDING:
|
||||
for (var i = 0; i < SERVO_CONFIG.length; i++) {
|
||||
var out = SERVO_CONFIG[i].indexOfChannelToForward;
|
||||
|
@ -1143,7 +1146,102 @@ MSP.dataflashRead = function(address, onDataCallback) {
|
|||
onDataCallback(address, null);
|
||||
}
|
||||
});
|
||||
} ;
|
||||
};
|
||||
|
||||
MSP.sendServoMixRules = function(onCompleteCallback) {
|
||||
// TODO implement
|
||||
onCompleteCallback();
|
||||
};
|
||||
|
||||
MSP.sendServoConfigurations = function(onCompleteCallback) {
|
||||
var nextFunction = send_next_servo_configuration;
|
||||
|
||||
var servoIndex = 0;
|
||||
|
||||
if (SERVO_CONFIG.length == 0) {
|
||||
onCompleteCallback();
|
||||
}
|
||||
|
||||
nextFunction();
|
||||
|
||||
function send_next_servo_configuration() {
|
||||
|
||||
var buffer = [];
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, "1.12.0")) {
|
||||
// send all in one go
|
||||
// 1.9.0 had a bug where the MSP input buffer was too small, limit to 8.
|
||||
for (var i = 0; i < SERVO_CONFIG.length && i < 8; i++) {
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].min));
|
||||
buffer.push(highByte(SERVO_CONFIG[i].min));
|
||||
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].max));
|
||||
buffer.push(highByte(SERVO_CONFIG[i].max));
|
||||
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].middle));
|
||||
buffer.push(highByte(SERVO_CONFIG[i].middle));
|
||||
|
||||
buffer.push(lowByte(SERVO_CONFIG[i].rate));
|
||||
}
|
||||
|
||||
nextFunction = send_channel_forwarding;
|
||||
} else {
|
||||
// send one at a time, with index
|
||||
|
||||
var servoConfiguration = SERVO_CONFIG[servoIndex];
|
||||
|
||||
buffer.push(servoIndex);
|
||||
|
||||
buffer.push(lowByte(servoConfiguration.min));
|
||||
buffer.push(highByte(servoConfiguration.min));
|
||||
|
||||
buffer.push(lowByte(servoConfiguration.max));
|
||||
buffer.push(highByte(servoConfiguration.max));
|
||||
|
||||
buffer.push(lowByte(servoConfiguration.middle));
|
||||
buffer.push(highByte(servoConfiguration.middle));
|
||||
|
||||
buffer.push(lowByte(servoConfiguration.rate));
|
||||
|
||||
buffer.push(servoConfiguration.angleAtMin);
|
||||
buffer.push(servoConfiguration.angleAtMax);
|
||||
|
||||
var out = servoConfiguration.indexOfChannelToForward;
|
||||
if (out == undefined) {
|
||||
out = 255; // Cleanflight defines "CHANNEL_FORWARDING_DISABLED" as "(uint8_t)0xFF"
|
||||
}
|
||||
buffer.push(out);
|
||||
|
||||
buffer.push(specificByte(servoConfiguration.reversedInputSources, 0));
|
||||
buffer.push(specificByte(servoConfiguration.reversedInputSources, 1));
|
||||
buffer.push(specificByte(servoConfiguration.reversedInputSources, 2));
|
||||
buffer.push(specificByte(servoConfiguration.reversedInputSources, 3));
|
||||
|
||||
// prepare for next iteration
|
||||
servoIndex++;
|
||||
if (servoIndex == SERVO_CONFIG.length) {
|
||||
nextFunction = onCompleteCallback;
|
||||
}
|
||||
}
|
||||
MSP.send_message(MSP_codes.MSP_SET_SERVO_CONFIGURATION, buffer, false, nextFunction);
|
||||
}
|
||||
|
||||
function send_channel_forwarding() {
|
||||
var buffer = [];
|
||||
|
||||
for (var 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"
|
||||
}
|
||||
buffer.push(out);
|
||||
}
|
||||
|
||||
nextFunction = onCompleteCallback;
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_SET_CHANNEL_FORWARDING, buffer, false, nextFunction);
|
||||
}
|
||||
};
|
||||
|
||||
MSP.sendModeRanges = function(onCompleteCallback) {
|
||||
var nextFunction = send_next_mode_range;
|
||||
|
@ -1161,12 +1259,12 @@ MSP.sendModeRanges = function(onCompleteCallback) {
|
|||
|
||||
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);
|
||||
var buffer = [];
|
||||
buffer.push(modeRangeIndex);
|
||||
buffer.push(modeRange.id);
|
||||
buffer.push(modeRange.auxChannelIndex);
|
||||
buffer.push((modeRange.range.start - 900) / 25);
|
||||
buffer.push((modeRange.range.end - 900) / 25);
|
||||
|
||||
// prepare for next iteration
|
||||
modeRangeIndex++;
|
||||
|
@ -1174,7 +1272,7 @@ MSP.sendModeRanges = function(onCompleteCallback) {
|
|||
nextFunction = onCompleteCallback;
|
||||
|
||||
}
|
||||
MSP.send_message(MSP_codes.MSP_SET_MODE_RANGE, AUX_val_buffer_out, false, nextFunction);
|
||||
MSP.send_message(MSP_codes.MSP_SET_MODE_RANGE, buffer, false, nextFunction);
|
||||
}
|
||||
};
|
||||
|
||||
|
@ -1194,14 +1292,14 @@ MSP.sendAdjustmentRanges = function(onCompleteCallback) {
|
|||
|
||||
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);
|
||||
var buffer = [];
|
||||
buffer.push(adjustmentRangeIndex);
|
||||
buffer.push(adjustmentRange.slotIndex);
|
||||
buffer.push(adjustmentRange.auxChannelIndex);
|
||||
buffer.push((adjustmentRange.range.start - 900) / 25);
|
||||
buffer.push((adjustmentRange.range.end - 900) / 25);
|
||||
buffer.push(adjustmentRange.adjustmentFunction);
|
||||
buffer.push(adjustmentRange.auxSwitchChannelIndex);
|
||||
|
||||
// prepare for next iteration
|
||||
adjustmentRangeIndex++;
|
||||
|
@ -1209,7 +1307,7 @@ MSP.sendAdjustmentRanges = function(onCompleteCallback) {
|
|||
nextFunction = onCompleteCallback;
|
||||
|
||||
}
|
||||
MSP.send_message(MSP_codes.MSP_SET_ADJUSTMENT_RANGE, ADJUSTMENT_val_buffer_out, false, nextFunction);
|
||||
MSP.send_message(MSP_codes.MSP_SET_ADJUSTMENT_RANGE, buffer, false, nextFunction);
|
||||
}
|
||||
};
|
||||
|
||||
|
|
|
@ -15,15 +15,25 @@ TABS.servos.initialize = function (callback) {
|
|||
googleAnalytics.sendAppView('Servos');
|
||||
}
|
||||
|
||||
function get_servo_conf_data() {
|
||||
MSP.send_message(MSP_codes.MSP_SERVO_CONF, false, false, get_channel_forwarding_data);
|
||||
function get_servo_configurations() {
|
||||
MSP.send_message(MSP_codes.MSP_SERVO_CONFIGURATIONS, false, false, get_servo_mix_rules);
|
||||
}
|
||||
|
||||
function get_channel_forwarding_data() {
|
||||
MSP.send_message(MSP_codes.MSP_CHANNEL_FORWARDING, false, false, get_rc_data);
|
||||
function get_servo_mix_rules() {
|
||||
MSP.send_message(MSP_codes.MSP_SERVO_MIX_RULES, false, false, get_channel_forwarding);
|
||||
}
|
||||
|
||||
function get_rc_data() {
|
||||
function get_channel_forwarding() {
|
||||
var nextFunction = get_rc_data;
|
||||
|
||||
if (semver.lt(CONFIG.apiVersion, "1.12.0")) {
|
||||
MSP.send_message(MSP_codes.MSP_CHANNEL_FORWARDING, false, false, nextFunction);
|
||||
} else {
|
||||
nextFunction();
|
||||
}
|
||||
}
|
||||
|
||||
function get_rc_data() {
|
||||
MSP.send_message(MSP_codes.MSP_RC, false, false, get_boxnames_data);
|
||||
}
|
||||
|
||||
|
@ -35,7 +45,7 @@ TABS.servos.initialize = function (callback) {
|
|||
$('#content').load("./tabs/servos.html", process_html);
|
||||
}
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_IDENT, false, false, get_servo_conf_data);
|
||||
MSP.send_message(MSP_codes.MSP_IDENT, false, false, get_servo_configurations);
|
||||
|
||||
function process_html() {
|
||||
|
||||
|
@ -104,10 +114,12 @@ TABS.servos.initialize = function (callback) {
|
|||
|
||||
|
||||
|
||||
// translate to user-selected language
|
||||
localize();
|
||||
// translate to user-selected language
|
||||
localize();
|
||||
|
||||
$('div.tab-servos table.fields tr:last td.channel input').eq(SERVO_CONFIG[obj].indexOfChannelToForward).prop('checked', true);
|
||||
if (SERVO_CONFIG[obj].indexOfChannelToForward >= 0) {
|
||||
$('div.tab-servos table.fields tr:last td.channel input').eq(SERVO_CONFIG[obj].indexOfChannelToForward).prop('checked', true);
|
||||
}
|
||||
|
||||
if (directions == true) {
|
||||
$('div.tab-servos table.fields tr:last td.direction input:first').prop('checked', bit_check(SERVO_CONFIG[obj].rate, 0));
|
||||
|
@ -146,7 +158,7 @@ TABS.servos.initialize = function (callback) {
|
|||
});
|
||||
}
|
||||
|
||||
function servos_update(save_to_eeprom) {
|
||||
function servos_update(save_configuration_to_eeprom) {
|
||||
// update bitfields
|
||||
$('div.tab-servos table.directions tr:not(".main")').each(function () {
|
||||
var info = $('select', this).data('info');
|
||||
|
@ -188,9 +200,27 @@ TABS.servos.initialize = function (callback) {
|
|||
}
|
||||
});
|
||||
|
||||
//
|
||||
// send data to FC
|
||||
//
|
||||
MSP.sendServoConfigurations(send_servo_mixer_rules);
|
||||
|
||||
function send_servo_mixer_rules() {
|
||||
MSP.sendServoConfigurations(save_to_eeprom);
|
||||
}
|
||||
|
||||
function save_to_eeprom() {
|
||||
if (save_configuration_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) {
|
||||
if (save_configuration_to_eeprom) {
|
||||
// Save changes to EEPROM
|
||||
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () {
|
||||
GUI.log(chrome.i18n.getMessage('servosEepromSave'));
|
||||
|
@ -198,6 +228,7 @@ TABS.servos.initialize = function (callback) {
|
|||
}
|
||||
});
|
||||
});
|
||||
*/
|
||||
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue