First cut of functional 'Ports' tab. Support backup and restore of
serial port scenarios and baud rates. Add note to 'features' tab.10.3.x-maintenance
parent
68230b103e
commit
d671bff583
|
@ -344,6 +344,10 @@
|
|||
"configurationFeatures": {
|
||||
"message": "Features"
|
||||
},
|
||||
"configurationFeaturesHelp": {
|
||||
"message": "<strong>Note:</strong> that not all combinations of features are valid. When the flight controller firmware detects this conflicting features will be disabled.<br /><strong>Note:</strong> Configure serial ports <span style=\"color: red\">before</span> enabling the features that will use the ports."
|
||||
},
|
||||
|
||||
"configurationBoardAlignment": {
|
||||
"message": "Board Alignment"
|
||||
},
|
||||
|
@ -435,6 +439,9 @@
|
|||
"message": "Save and Reboot"
|
||||
},
|
||||
|
||||
"portsHelp": {
|
||||
"message": "Configure serial ports. <strong>Note:</strong> that not all ports support all scenarios and not all combinations of scenarios are valid. When the flight controller firmware detects this the serial port configuration will be reset."
|
||||
},
|
||||
"portsButtonSave": {
|
||||
"message": "Save and Reboot"
|
||||
},
|
||||
|
|
|
@ -23,7 +23,8 @@ function configuration_backup(callback) {
|
|||
*/
|
||||
MSP_codes.MSP_MISC,
|
||||
MSP_codes.MSP_RCMAP,
|
||||
MSP_codes.MSP_BF_CONFIG
|
||||
MSP_codes.MSP_BF_CONFIG,
|
||||
MSP_codes.MSP_CF_SERIAL_CONFIG
|
||||
];
|
||||
|
||||
var configuration = {
|
||||
|
@ -97,6 +98,7 @@ function configuration_backup(callback) {
|
|||
configuration.MISC = jQuery.extend(true, {}, MISC);
|
||||
configuration.RCMAP = jQuery.extend(true, [], RC_MAP);
|
||||
configuration.BF_CONFIG = jQuery.extend(true, {}, BF_CONFIG);
|
||||
configuration.SERIAL_CONFIG = jQuery.extend(true, {}, SERIAL_CONFIG);
|
||||
|
||||
save();
|
||||
}
|
||||
|
@ -285,7 +287,8 @@ function configuration_restore(callback) {
|
|||
*/
|
||||
MSP_codes.MSP_SET_MISC,
|
||||
MSP_codes.MSP_SET_RCMAP,
|
||||
MSP_codes.MSP_SET_CONFIG
|
||||
MSP_codes.MSP_SET_BF_CONFIG,
|
||||
MSP_codes.MSP_SET_CF_SERIAL_CONFIG
|
||||
];
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_STATUS, false, false, function () {
|
||||
|
@ -362,6 +365,7 @@ function configuration_restore(callback) {
|
|||
MISC = configuration.MISC;
|
||||
RC_MAP = configuration.RCMAP;
|
||||
BF_CONFIG = configuration.BF_CONFIG;
|
||||
SERIAL_CONFIG = configuration.SERIAL_CONFIG;
|
||||
}
|
||||
|
||||
function query() {
|
||||
|
|
|
@ -0,0 +1,67 @@
|
|||
'use strict';
|
||||
|
||||
var BOARD_DEFINITIONS = [
|
||||
{
|
||||
name: "CC3D",
|
||||
identifier: "CC3D",
|
||||
serialPortCount: 3
|
||||
}, {
|
||||
name: "ChebuzzF3",
|
||||
identifier: "CHF3",
|
||||
serialPortCount: 3
|
||||
}, {
|
||||
name: "CJMCU",
|
||||
identifier: "CJM1",
|
||||
serialPortCount: 2
|
||||
}, {
|
||||
name: "EUSTM32F103RB",
|
||||
identifier: "EUF1",
|
||||
serialPortCount: 4
|
||||
}, {
|
||||
name: "Naze/Flip32+",
|
||||
identifier: "AFNA",
|
||||
serialPortCount: 4
|
||||
}, {
|
||||
name: "Naze32Pro",
|
||||
identifier: "AFF3",
|
||||
serialPortCount: 3
|
||||
}, {
|
||||
name: "Olimexino",
|
||||
identifier: "OLI1",
|
||||
serialPortCount: 4
|
||||
}, {
|
||||
name: "Port103R",
|
||||
identifier: "103R",
|
||||
serialPortCount: 4
|
||||
}, {
|
||||
name: "Sparky",
|
||||
identifier: "SPKY",
|
||||
serialPortCount: 4
|
||||
}, {
|
||||
name: "STM32F3Discovery",
|
||||
identifier: "SDF3",
|
||||
serialPortCount: 3
|
||||
}
|
||||
];
|
||||
|
||||
var DEFAULT_BOARD_DEFINITION = {
|
||||
name: "Unknown",
|
||||
identifier: "????",
|
||||
serialPortCount: 1
|
||||
};
|
||||
|
||||
var BOARD = {
|
||||
|
||||
};
|
||||
|
||||
BOARD.find_board_definition = function (identifier) {
|
||||
for (var i = 0; i < BOARD_DEFINITIONS.length; i++) {
|
||||
var candidate = BOARD_DEFINITIONS[i];
|
||||
|
||||
if (candidate.identifier == identifier) {
|
||||
return candidate;
|
||||
}
|
||||
}
|
||||
return DEFAULT_BOARD_DEFINITION;
|
||||
};
|
||||
|
|
@ -75,6 +75,14 @@ var ADJUSTMENT_RANGES = [];
|
|||
|
||||
var SERVO_CONFIG = [];
|
||||
|
||||
var SERIAL_CONFIG = {
|
||||
ports: [],
|
||||
mspBaudRate: 0,
|
||||
gpsBaudRate: 0,
|
||||
gpsPassthroughBaudRate: 0,
|
||||
cliBaudRate: 0,
|
||||
};
|
||||
|
||||
var SENSOR_DATA = {
|
||||
gyroscope: [0, 0, 0],
|
||||
accelerometer: [0, 0, 0],
|
||||
|
|
51
js/msp.js
51
js/msp.js
|
@ -15,6 +15,8 @@ var MSP_codes = {
|
|||
MSP_SET_MODE_RANGE: 35,
|
||||
MSP_ADJUSTMENT_RANGES: 52,
|
||||
MSP_SET_ADJUSTMENT_RANGE: 53,
|
||||
MSP_CF_SERIAL_CONFIG: 54,
|
||||
MSP_SET_CF_SERIAL_CONFIG: 55,
|
||||
|
||||
// Multiwii MSP commands
|
||||
MSP_IDENT: 100,
|
||||
|
@ -539,7 +541,28 @@ var MSP = {
|
|||
case MSP_codes.MSP_SET_CHANNEL_FORWARDING:
|
||||
console.log('Channel forwarding saved');
|
||||
break;
|
||||
|
||||
|
||||
case MSP_codes.MSP_CF_SERIAL_CONFIG:
|
||||
SERIAL_CONFIG.ports = [];
|
||||
var offset = 0;
|
||||
var serialPortCount = data.byteLength - (4 * 4);
|
||||
for (var i = 0; offset < serialPortCount; i++) {
|
||||
var serialPort = {
|
||||
identifier: data.getUint8(offset++, 1),
|
||||
scenario: data.getUint8(offset++, 1)
|
||||
}
|
||||
SERIAL_CONFIG.ports.push(serialPort);
|
||||
}
|
||||
SERIAL_CONFIG.mspBaudRate = data.getUint32(offset, 1);
|
||||
offset+= 4;
|
||||
SERIAL_CONFIG.cliBaudRate = data.getUint32(offset, 1);
|
||||
offset+= 4;
|
||||
SERIAL_CONFIG.gpsBaudRate = data.getUint32(offset, 1);
|
||||
offset+= 4;
|
||||
SERIAL_CONFIG.gpsPassthroughBaudRate = data.getUint32(offset, 1);
|
||||
offset+= 4;
|
||||
break;
|
||||
|
||||
case MSP_codes.MSP_MODE_RANGES:
|
||||
MODE_RANGES = []; // empty the array as new data is coming in
|
||||
|
||||
|
@ -706,7 +729,7 @@ MSP.crunch = function (code) {
|
|||
var buffer = [];
|
||||
|
||||
switch (code) {
|
||||
case MSP_codes.MSP_SET_CONFIG:
|
||||
case MSP_codes.MSP_SET_BF_CONFIG:
|
||||
buffer.push(BF_CONFIG.mixerConfiguration);
|
||||
buffer.push(specificByte(BF_CONFIG.features, 0));
|
||||
buffer.push(specificByte(BF_CONFIG.features, 1));
|
||||
|
@ -824,6 +847,30 @@ MSP.crunch = function (code) {
|
|||
buffer.push(SERVO_CONFIG[i].indexOfChannelToForward);
|
||||
}
|
||||
break;
|
||||
case MSP_codes.MSP_SET_CF_SERIAL_CONFIG:
|
||||
for (var i = 0; i < SERIAL_CONFIG.ports.length; i++) {
|
||||
buffer.push(SERIAL_CONFIG.ports[i].scenario);
|
||||
}
|
||||
buffer.push(specificByte(SERIAL_CONFIG.mspBaudRate, 0));
|
||||
buffer.push(specificByte(SERIAL_CONFIG.mspBaudRate, 1));
|
||||
buffer.push(specificByte(SERIAL_CONFIG.mspBaudRate, 2));
|
||||
buffer.push(specificByte(SERIAL_CONFIG.mspBaudRate, 3));
|
||||
|
||||
buffer.push(specificByte(SERIAL_CONFIG.cliBaudRate, 0));
|
||||
buffer.push(specificByte(SERIAL_CONFIG.cliBaudRate, 1));
|
||||
buffer.push(specificByte(SERIAL_CONFIG.cliBaudRate, 2));
|
||||
buffer.push(specificByte(SERIAL_CONFIG.cliBaudRate, 3));
|
||||
|
||||
buffer.push(specificByte(SERIAL_CONFIG.gpsBaudRate, 0));
|
||||
buffer.push(specificByte(SERIAL_CONFIG.gpsBaudRate, 1));
|
||||
buffer.push(specificByte(SERIAL_CONFIG.gpsBaudRate, 2));
|
||||
buffer.push(specificByte(SERIAL_CONFIG.gpsBaudRate, 3));
|
||||
|
||||
buffer.push(specificByte(SERIAL_CONFIG.gpsPassthroughBaudRate, 0));
|
||||
buffer.push(specificByte(SERIAL_CONFIG.gpsPassthroughBaudRate, 1));
|
||||
buffer.push(specificByte(SERIAL_CONFIG.gpsPassthroughBaudRate, 2));
|
||||
buffer.push(specificByte(SERIAL_CONFIG.gpsPassthroughBaudRate, 3));
|
||||
break;
|
||||
|
||||
default:
|
||||
return false;
|
||||
|
|
12
main.html
12
main.html
|
@ -10,8 +10,8 @@
|
|||
|
||||
<link type="text/css" rel="stylesheet" href="./tabs/landing.css" media="all" />
|
||||
<link type="text/css" rel="stylesheet" href="./tabs/setup.css" media="all" />
|
||||
<link type="text/css" rel="stylesheet" href="./tabs/configuration.css" media="all" />
|
||||
<link type="text/css" rel="stylesheet" href="./tabs/ports.css" media="all" />
|
||||
<link type="text/css" rel="stylesheet" href="./tabs/configuration.css" media="all" />
|
||||
<link type="text/css" rel="stylesheet" href="./tabs/pid_tuning.css" media="all" />
|
||||
<link type="text/css" rel="stylesheet" href="./tabs/receiver.css" media="all" />
|
||||
<!-- <link type="text/css" rel="stylesheet" href="./tabs/modes.css" media="all" /> -->
|
||||
|
@ -47,18 +47,18 @@
|
|||
<script type="text/javascript" src="./js/protocols/stm32.js"></script>
|
||||
<script type="text/javascript" src="./js/protocols/stm32usbdfu.js"></script>
|
||||
<script type="text/javascript" src="./js/localization.js"></script>
|
||||
<script type="text/javascript" src="./js/boards.js"></script>
|
||||
<script type="text/javascript" src="./main.js"></script>
|
||||
|
||||
<script type="text/javascript" src="./tabs/adjustments.js"></script>
|
||||
<script type="text/javascript" src="./tabs/auxiliary.js"></script>
|
||||
|
||||
<script type="text/javascript" src="./tabs/landing.js"></script>
|
||||
<script type="text/javascript" src="./tabs/setup.js"></script>
|
||||
<script type="text/javascript" src="./tabs/configuration.js"></script>
|
||||
<script type="text/javascript" src="./tabs/ports.js"></script>
|
||||
<script type="text/javascript" src="./tabs/configuration.js"></script>
|
||||
<script type="text/javascript" src="./tabs/pid_tuning.js"></script>
|
||||
<script type="text/javascript" src="./tabs/receiver.js"></script>
|
||||
<!-- <script type="text/javascript" src="./tabs/modes.js"></script> -->
|
||||
<script type="text/javascript" src="./tabs/auxiliary.js"></script>
|
||||
<script type="text/javascript" src="./tabs/adjustments.js"></script>
|
||||
<script type="text/javascript" src="./tabs/servos.js"></script>
|
||||
<script type="text/javascript" src="./tabs/gps.js"></script>
|
||||
<script type="text/javascript" src="./tabs/motors.js"></script>
|
||||
|
@ -119,8 +119,8 @@
|
|||
<div id="tabs">
|
||||
<ul>
|
||||
<li class="tab_setup"><a href="#" i18n="tabSetup"></a></li>
|
||||
<li class="tab_configuration"><a href="#" i18n="tabConfiguration"></a></li>
|
||||
<li class="tab_ports"><a href="#" i18n="tabPorts"></a></li>
|
||||
<li class="tab_configuration"><a href="#" i18n="tabConfiguration"></a></li>
|
||||
<li class="tab_pid_tuning"><a href="#" i18n="tabPidTuning"></a></li>
|
||||
<li class="tab_receiver"><a href="#" i18n="tabReceiver"></a></li>
|
||||
<!-- <li class="tab_modes"><a href="#" i18n="tabModeSelection"></a></li> -->
|
||||
|
|
|
@ -30,7 +30,6 @@
|
|||
white-space: nowrap;
|
||||
padding: 10px 10px;
|
||||
background-color: #61B665;
|
||||
|
||||
}
|
||||
|
||||
.tab-adjustments .adjustment {
|
||||
|
|
|
@ -1,11 +1,11 @@
|
|||
<div class="tab-adjustments">
|
||||
<div class="help">
|
||||
<p i18n="adjustmentsHelp"></p>
|
||||
<p i18n="adjustmentsExamples"></p>
|
||||
<ul>
|
||||
<li i18n="adjustmentsExample1"></li>
|
||||
<li i18n="adjustmentsExample2"></li>
|
||||
</ul>
|
||||
<p i18n="adjustmentsHelp"></p>
|
||||
<p i18n="adjustmentsExamples"></p>
|
||||
<ul>
|
||||
<li i18n="adjustmentsExample1"></li>
|
||||
<li i18n="adjustmentsExample2"></li>
|
||||
</ul>
|
||||
</div>
|
||||
<table class="adjustments">
|
||||
<thead>
|
||||
|
|
|
@ -1,3 +1,7 @@
|
|||
.tab-configuration .help {
|
||||
float: left;
|
||||
}
|
||||
|
||||
.tab-configuration table {
|
||||
float: left;
|
||||
|
||||
|
@ -17,7 +21,9 @@
|
|||
.tab-configuration table td {
|
||||
padding: 2px 10px;
|
||||
}
|
||||
.tab-configuration table tr:nth-child(odd) {
|
||||
|
||||
.tab-configuration table thead tr:first-child,
|
||||
.tab-configuration table tr:nth-child(even) {
|
||||
background-color: #ececec;
|
||||
}
|
||||
|
||||
|
|
|
@ -22,6 +22,9 @@
|
|||
<!-- table generated here -->
|
||||
</tbody>
|
||||
</table>
|
||||
<div class="help">
|
||||
<p i18n="configurationFeaturesHelp"></p>
|
||||
</div>
|
||||
</div>
|
||||
<div class="clear-both"></div>
|
||||
<div class="leftWrapper">
|
||||
|
|
|
@ -268,7 +268,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
|||
},1500); // 1500 ms seems to be just the right amount of delay to prevent data request timeouts
|
||||
}
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_SET_BF_CONFIG, MSP.crunch(MSP_codes.MSP_SET_CONFIG), false, save_misc);
|
||||
MSP.send_message(MSP_codes.MSP_SET_BF_CONFIG, MSP.crunch(MSP_codes.MSP_SET_BF_CONFIG), false, save_misc);
|
||||
});
|
||||
|
||||
// status data pulled via separate timer with static speed
|
||||
|
|
|
@ -2,6 +2,42 @@
|
|||
position: relative;
|
||||
}
|
||||
|
||||
#tab-ports-templates {
|
||||
display: none;
|
||||
}
|
||||
|
||||
.tab-ports .help {
|
||||
padding: 10px;
|
||||
background-color: #ffcb18;
|
||||
margin-bottom: 10px;
|
||||
}
|
||||
|
||||
.tab-ports table {
|
||||
margin-bottom: 10px;
|
||||
|
||||
border-collapse: collapse;
|
||||
}
|
||||
.tab-ports table,
|
||||
.tab-ports table th,
|
||||
.tab-ports table td {
|
||||
padding: 4px;
|
||||
border: 1px solid #8b8b8b;
|
||||
}
|
||||
.tab-ports table tr td:first-child {
|
||||
text-align: center;
|
||||
}
|
||||
.tab-ports table td {
|
||||
padding: 2px 10px;
|
||||
}
|
||||
|
||||
.tab-ports table thead tr:first-child,
|
||||
.tab-ports table tr:nth-child(even) {
|
||||
background-color: #ececec;
|
||||
}
|
||||
|
||||
.tab-ports select {
|
||||
border: 1px solid silver;
|
||||
}
|
||||
.tab-ports > .buttons {
|
||||
width: calc(100% - 20px);
|
||||
|
||||
|
|
|
@ -1,6 +1,38 @@
|
|||
<div class="tab-ports">
|
||||
<div class="help">
|
||||
<p i18n="portsHelp"></p>
|
||||
</div>
|
||||
<table class="ports">
|
||||
<thead>
|
||||
<tr>
|
||||
<td>Identifier</td>
|
||||
<td>Scenario</td>
|
||||
</tr>
|
||||
</thead>
|
||||
<tbody>
|
||||
</tbody>
|
||||
</table>
|
||||
<div class="clear-both"></div>
|
||||
<div class="buttons">
|
||||
<a class="save" href="#" i18n="portsButtonSave"></a>
|
||||
</div>
|
||||
</div>
|
||||
|
||||
<div id="tab-ports-templates">
|
||||
<table class="ports">
|
||||
<thead>
|
||||
</thead>
|
||||
<tbody>
|
||||
<tr class="portConfiguration">
|
||||
<td class="identifierCell">
|
||||
<p class="identifier"></p>
|
||||
</td>
|
||||
<td class="scenarioCell">
|
||||
<select class="scenario">
|
||||
<!-- list generated here -->
|
||||
</select>
|
||||
</td>
|
||||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
</div>
|
|
@ -5,6 +5,8 @@ TABS.ports = {};
|
|||
TABS.ports.initialize = function (callback, scrollPosition) {
|
||||
var self = this;
|
||||
|
||||
var board_definition = {};
|
||||
|
||||
if (GUI.active_tab != 'ports') {
|
||||
GUI.active_tab = 'ports';
|
||||
googleAnalytics.sendAppView('Ports');
|
||||
|
@ -13,20 +15,70 @@ TABS.ports.initialize = function (callback, scrollPosition) {
|
|||
load_configuration_from_fc();
|
||||
|
||||
function load_configuration_from_fc() {
|
||||
MSP.send_message(MSP_codes.MSP_IDENT, false, false, on_ident_loaded_handler);
|
||||
|
||||
function on_ident_loaded_handler() {
|
||||
MSP.send_message(MSP_codes.MSP_BF_CONFIG, false, false, on_configuration_loaded_handler);
|
||||
}
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_CF_SERIAL_CONFIG, false, false, on_configuration_loaded_handler);
|
||||
|
||||
function on_configuration_loaded_handler() {
|
||||
$('#content').load("./tabs/ports.html", on_tab_loaded_handler);
|
||||
|
||||
board_definition = BOARD.find_board_definition(CONFIG.boardIdentifier);
|
||||
console.log('Using board definition', board_definition);
|
||||
}
|
||||
}
|
||||
|
||||
function addSerialPortScenarios() {
|
||||
|
||||
var scenarioNames = [
|
||||
'Unused',
|
||||
'MSP, CLI, Telemetry (when armed), GPS Passthrough',
|
||||
'GPS',
|
||||
'Serial RX',
|
||||
'Telemetry',
|
||||
'MSP, CLI, GPS Passthrough',
|
||||
'CLI',
|
||||
'GPS Passthrough',
|
||||
'MSP',
|
||||
'SmartPort Telemetry'
|
||||
];
|
||||
|
||||
var portIdentifierToNameMapping = {
|
||||
0: 'UART1',
|
||||
1: 'UART2',
|
||||
2: 'UART3',
|
||||
3: 'UART4',
|
||||
20: 'USB VCP',
|
||||
30: 'SOFTSERIAL1',
|
||||
31: 'SOFTSERIAL2'
|
||||
};
|
||||
|
||||
var scenario_e = $('#tab-ports-templates select.scenario');
|
||||
|
||||
for (var i = 0; i < scenarioNames.length; i++) {
|
||||
scenario_e.append('<option value="' + i + '">' + scenarioNames[i] + '</option>');
|
||||
}
|
||||
|
||||
var ports_e = $('.tab-ports .ports');
|
||||
var port_configuration_template_e = $('#tab-ports-templates .portConfiguration');
|
||||
|
||||
for (var portIndex = 0; portIndex < board_definition.serialPortCount; portIndex++) {
|
||||
var port_configuration_e = port_configuration_template_e.clone();
|
||||
|
||||
var serialPort = SERIAL_CONFIG.ports[portIndex];
|
||||
|
||||
port_configuration_e.find('select').val(serialPort.scenario);
|
||||
port_configuration_e.find('.identifier').text(portIdentifierToNameMapping[serialPort.identifier])
|
||||
|
||||
port_configuration_e.data('index', portIndex);
|
||||
port_configuration_e.data('port', serialPort);
|
||||
|
||||
ports_e.find('tbody').append(port_configuration_e);
|
||||
}
|
||||
}
|
||||
|
||||
function on_tab_loaded_handler() {
|
||||
|
||||
localize();
|
||||
|
||||
addSerialPortScenarios();
|
||||
|
||||
$('a.save').click(on_save_handler);
|
||||
|
||||
|
@ -40,7 +92,15 @@ TABS.ports.initialize = function (callback, scrollPosition) {
|
|||
|
||||
function on_save_handler() {
|
||||
|
||||
MSP.send_message(MSP_codes.MSP_SET_CONFIG, MSP.crunch(MSP_codes.MSP_SET_CONFIG), false, save_to_eeprom);
|
||||
// update configuration based on current ui state
|
||||
var ports_e = $('.tab-ports .portConfiguration').each(function () {
|
||||
var portIndex = $(this).data('index');
|
||||
|
||||
SERIAL_CONFIG.ports[portIndex].scenario = parseInt($(this).find('select').val());
|
||||
});
|
||||
|
||||
|
||||
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() {
|
||||
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, on_saved_handler);
|
||||
|
|
Loading…
Reference in New Issue