diff --git a/_locales/en/messages.json b/_locales/en/messages.json
index 8f1944be..e4cebe28 100755
--- a/_locales/en/messages.json
+++ b/_locales/en/messages.json
@@ -521,6 +521,30 @@
"portsButtonSave": {
"message": "Save and Reboot"
},
+ "portsFunction_MSP": {
+ "message": "MSP"
+ },
+ "portsFunction_GSP": {
+ "message": "GSP"
+ },
+ "portsFunction_TELEMETRY_FRSKY": {
+ "message": "FrSky"
+ },
+ "portsFunction_TELEMETRY_HOTT": {
+ "message": "HoTT"
+ },
+ "portsFunction_TELEMETRY_MSP": {
+ "message": "MSP"
+ },
+ "portsFunction_TELEMETRY_SMARTPORT": {
+ "message": "SmartPort"
+ },
+ "portsFunction_RX_SERIAL": {
+ "message": "Serial RX"
+ },
+ "portsFunction_BLACKBOX": {
+ "message": "Blackbox"
+ },
"pidTuningUpgradeFirmwareToChangePidController": {
"message": "Changing PID controller disabled - you can change it via the CLI. You have firmware with API version $1, but this functionality requires requires $2."
diff --git a/js/msp.js b/js/msp.js
index 459222e3..81f12061 100644
--- a/js/msp.js
+++ b/js/msp.js
@@ -110,6 +110,9 @@ var MSP = {
'57600',
'115200'
],
+
+ serialPortFunctions: // in LSB bit order
+ ['MSP', 'GPS', 'TELEMETRY_FRSKY', 'TELEMETRY_HOTT', 'TELEMETRY_MSP', 'TELEMETRY_SMARTPORT', 'RX_SERIAL', 'BLACKBOX'],
read: function (readInfo) {
var data = new Uint8Array(readInfo.data);
@@ -595,7 +598,7 @@ var MSP = {
for (var i = 0; i < serialPortCount; i++) {
var serialPort = {
identifier: data.getUint8(offset, 1),
- functionMask: data.getUint16(offset + 1, 1),
+ functions: MSP.serialPortFunctionMaskToFunctions(data.getUint16(offset + 1, 1)),
msp_baudrate: MSP.supportedBaudRates[data.getUint8(offset + 3, 1)],
gps_baudrate: MSP.supportedBaudRates[data.getUint8(offset + 4, 1)],
telemetry_baudrate: MSP.supportedBaudRates[data.getUint8(offset + 5, 1)],
@@ -1008,7 +1011,20 @@ MSP.crunch = function (code) {
buffer.push(specificByte(SERIAL_CONFIG.gpsPassthroughBaudRate, 2));
buffer.push(specificByte(SERIAL_CONFIG.gpsPassthroughBaudRate, 3));
} else {
- console.log('unsupported');
+ for (var i = 0; i < SERIAL_CONFIG.ports.length; i++) {
+ var serialPort = SERIAL_CONFIG.ports[i];
+
+ buffer.push(serialPort.identifier);
+
+ var functionMask = MSP.serialPortFunctionsToMask(serialPort.functions);
+ buffer.push(specificByte(functionMask, 0));
+ buffer.push(specificByte(functionMask, 1));
+
+ buffer.push(MSP.supportedBaudRates.indexOf(serialPort.msp_baudrate));
+ buffer.push(MSP.supportedBaudRates.indexOf(serialPort.gps_baudrate));
+ buffer.push(MSP.supportedBaudRates.indexOf(serialPort.telemetry_baudrate));
+ buffer.push(MSP.supportedBaudRates.indexOf(serialPort.blackbox_baudrate));
+ }
}
break;
@@ -1165,3 +1181,24 @@ MSP.sendLedStripConfig = function(onCompleteCallback) {
}
}
+MSP.serialPortFunctionMaskToFunctions = function(functionMask) {
+ var functions = [];
+
+ for (var index = 0; index < MSP.serialPortFunctions.length; index++) {
+ if (bit_check(functionMask, index)) {
+ functions.push(MSP.serialPortFunctions[index]);
+ }
+ }
+ return functions;
+}
+
+MSP.serialPortFunctionsToMask = function(functions) {
+ var mask = 0;
+ for (var index = 0; index < functions.length; index++) {
+ var bitIndex = MSP.serialPortFunctions.indexOf(functions[index]);
+ if (bitIndex >= 0) {
+ mask = bit_set(mask, bitIndex);
+ }
+ }
+ return mask;
+}
diff --git a/tabs/ports.js b/tabs/ports.js
index cbbaa6fd..28a4564b 100644
--- a/tabs/ports.js
+++ b/tabs/ports.js
@@ -8,15 +8,19 @@ TABS.ports.initialize = function (callback, scrollPosition) {
var board_definition = {};
var functionRules = [
- {name: 'MSP', groups: ['data', 'msp'], maxPorts: 2},
- {name: 'GPS', groups: ['gps'], maxPorts: 1},
- {name: 'FrSky', groups: ['telemetry'], sharableWith: ['msp'], notSharableWith: ['blackbox'], maxPorts: 1},
- {name: 'HoTT', groups: ['telemetry'], sharableWith: ['msp'], notSharableWith: ['blackbox'], maxPorts: 1},
- {name: 'MSP', groups: ['telemetry'], sharableWith: ['msp'], notSharableWith: ['blackbox'], maxPorts: 1},
- {name: 'SmartPort', groups: ['telemetry'], maxPorts: 1},
- {name: 'Serial RX', groups: ['rx'], maxPorts: 1},
- {name: 'Blackbox', groups: ['logging', 'blackbox'], sharableWith: ['msp'], notSharableWith: ['telemetry'], maxPorts: 1},
+ {name: 'MSP', groups: ['data', 'msp'], maxPorts: 2},
+ {name: 'GPS', groups: ['gps'], maxPorts: 1},
+ {name: 'TELEMETRY_FRSKY', groups: ['telemetry'], sharableWith: ['msp'], notSharableWith: ['blackbox'], maxPorts: 1},
+ {name: 'TELEMETRY_HOTT', groups: ['telemetry'], sharableWith: ['msp'], notSharableWith: ['blackbox'], maxPorts: 1},
+ {name: 'TELEMETRY_MSP', groups: ['telemetry'], sharableWith: ['msp'], notSharableWith: ['blackbox'], maxPorts: 1},
+ {name: 'TELEMETRY_SMARTPORT', groups: ['telemetry'], maxPorts: 1},
+ {name: 'RX_SERIAL', groups: ['rx'], maxPorts: 1},
+ {name: 'BLACKBOX', groups: ['logging', 'blackbox'], sharableWith: ['msp'], notSharableWith: ['telemetry'], maxPorts: 1},
];
+
+ for (var i = 0; i < functionRules.length; i++) {
+ functionRules[i].displayName = chrome.i18n.getMessage('portsFunction_' + functionRules[i].name);
+ }
var mspBaudRates = [
'9600',
@@ -60,6 +64,8 @@ TABS.ports.initialize = function (callback, scrollPosition) {
MSP.send_message(MSP_codes.MSP_CF_SERIAL_CONFIG, false, false, on_configuration_loaded_handler);
function on_configuration_loaded_handler() {
+ console.log(SERIAL_CONFIG.ports);
+
$('#content').load("./tabs/ports.html", on_tab_loaded_handler);
board_definition = BOARD.find_board_definition(CONFIG.boardIdentifier);
@@ -100,34 +106,78 @@ TABS.ports.initialize = function (callback, scrollPosition) {
blackbox_baudrate_e.append('');
}
- for (var columnIndex = 0; columnIndex < columns.length; columnIndex++) {
- var column = columns[columnIndex];
-
- var functions_e = $('#tab-ports-templates .functionsCell-' + column);
-
- for (var i = 0; i < functionRules.length; i++) {
- if (functionRules[i].groups.indexOf(column) >= 0) {
- functions_e.prepend('');
- }
-
- }
- }
-
var ports_e = $('.tab-ports .ports');
var port_configuration_template_e = $('#tab-ports-templates .portConfiguration');
for (var portIndex = 0; portIndex < SERIAL_CONFIG.ports.length; portIndex++) {
var port_configuration_e = port_configuration_template_e.clone();
-
var serialPort = SERIAL_CONFIG.ports[portIndex];
-
+
+ port_configuration_e.data('serialPort', serialPort);
+
// TODO check functions
// TODO set baudrate
+ var msp_baudrate_e = port_configuration_e.find('select.msp_baudrate');
+ msp_baudrate_e.val(serialPort.msp_baudrate);
+
+ var telemetry_baudrate_e = port_configuration_e.find('select.telemetry_baudrate');
+ telemetry_baudrate_e.val(serialPort.telemetry_baudrate);
+
+ var gps_baudrate_e = port_configuration_e.find('select.gps_baudrate');
+ gps_baudrate_e.val(serialPort.gps_baudrate);
+
+ var blackbox_baudrate_e = port_configuration_e.find('select.blackbox_baudrate');
+ blackbox_baudrate_e.val(serialPort.blackbox_baudrate);
+
port_configuration_e.find('.identifier').text(portIdentifierToNameMapping[serialPort.identifier])
port_configuration_e.data('index', portIndex);
port_configuration_e.data('port', serialPort);
-
+
+
+ for (var columnIndex = 0; columnIndex < columns.length; columnIndex++) {
+ var column = columns[columnIndex];
+
+ var functions_e = $(port_configuration_e).find('.functionsCell-' + column);
+
+ for (var i = 0; i < functionRules.length; i++) {
+ var functionRule = functionRules[i];
+ var functionName = functionRule.name;
+
+ if (functionRule.groups.indexOf(column) == -1) {
+ continue;
+ }
+
+ var select_e;
+ if (column != 'telemetry') {
+ var checkboxId = 'functionCheckbox-' + portIndex + '-' + columnIndex + '-' + i;
+ functions_e.prepend('');
+
+ if (serialPort.functions.indexOf(functionName) >= 0) {
+ var checkbox_e = functions_e.find('#' + checkboxId);
+ checkbox_e.prop("checked", true);
+ }
+
+ } else {
+
+ var selectElementName = 'function-' + column;
+ var selectElementSelector = 'select[name=' + selectElementName + ']';
+ select_e = functions_e.find(selectElementSelector);
+
+ if (select_e.size() == 0) {
+ functions_e.prepend('');
+ select_e = functions_e.find(selectElementSelector);
+ select_e.append('');
+ }
+ select_e.append('');
+
+ if (serialPort.functions.indexOf(functionName) >= 0) {
+ select_e.val(functionName);
+ }
+ }
+ }
+ }
+
ports_e.find('tbody').append(port_configuration_e);
}
}
@@ -151,13 +201,37 @@ TABS.ports.initialize = function (callback, scrollPosition) {
function on_save_handler() {
// update configuration based on current ui state
- var ports_e = $('.tab-ports .portConfiguration').each(function () {
- var portIndex = $(this).data('index');
+ SERIAL_CONFIG.ports = [];
+
+ var ports_e = $('.tab-ports .portConfiguration').each(function (portConfiguration_e) {
- SERIAL_CONFIG.ports[portIndex].scenario = parseInt($(this).find('select').val());
+ var portConfiguration_e = this;
+
+ var oldSerialPort = $(this).data('serialPort');
+
+ var functions = $(portConfiguration_e).find('input:checkbox:checked').map(function() {
+ return this.value;
+ }).get();
+
+ var telemetryFunction = $(portConfiguration_e).find('select[name=function-telemetry]').val();
+ if (telemetryFunction) {
+ functions.push(telemetryFunction);
+ }
+
+ var serialPort = {
+ functions: functions,
+ msp_baudrate: $(portConfiguration_e).find('.msp_baudrate').val(),
+ telemetry_baudrate: $(portConfiguration_e).find('.telemetry_baudrate').val(),
+ gps_baudrate: $(portConfiguration_e).find('.gps_baudrate').val(),
+ blackbox_baudrate: $(portConfiguration_e).find('.blackbox_baudrate').val(),
+ identifier: oldSerialPort.identifier
+ };
+
+ console.log(serialPort);
+ SERIAL_CONFIG.ports.push(serialPort);
});
-
+
MSP.send_message(MSP_codes.MSP_SET_CF_SERIAL_CONFIG, MSP.crunch(MSP_codes.MSP_SET_CF_SERIAL_CONFIG), false, save_to_eeprom);
function save_to_eeprom() {