Merge pull request #1 from iNavFlight/master

Bump local repo
pull/1032/head
Daniel Ribeiro 5 years ago committed by GitHub
commit 16dc59f44f
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23

@ -26,6 +26,14 @@ Depending on target operating system, _INAV Configurator_ is distributed as _sta
1. Run INAV Configurator app from unpacked folder 1. Run INAV Configurator app from unpacked folder
1. Configurator is not signed, so you have to allow Windows to run untrusted application. There might be a monit for it during first run 1. Configurator is not signed, so you have to allow Windows to run untrusted application. There might be a monit for it during first run
### Linux
1. Visit [release page](https://github.com/iNavFlight/inav-configurator/releases)
1. Download Configurator for Linux platform (linux32 and linux64 are present)
1. Extract tar.gz archive
1. Make the inav-configurator file executable (chmod +x inav-configurator)
1. Run INAV Configurator app from unpacked folder
### Mac ### Mac
1. Visit [release page](https://github.com/iNavFlight/inav-configurator/releases) 1. Visit [release page](https://github.com/iNavFlight/inav-configurator/releases)
@ -46,7 +54,7 @@ For local development, **node.js** build system is used.
1. From project folder run `npm install` 1. From project folder run `npm install`
1. To build the JS and CSS files and start the configurator: 1. To build the JS and CSS files and start the configurator:
- With NW.js: Run `npm start`. - With NW.js: Run `npm start`.
- With Chrome: Run `./node_modules/gulp/bin/gulp.js`. Then open `chrome://extensions`, enable - With Chrome: Run `npm run gulp`. Then open `chrome://extensions`, enable
the `Developer mode`, click on the `Load unpacked extension...` button and select the `inav-configurator` directory. the `Developer mode`, click on the `Load unpacked extension...` button and select the `inav-configurator` directory.
Other tasks are also defined in `gulpfile.js`. To run a task, use `./node_modules/gulp/bin/gulp.js task-name`. Available ones are: Other tasks are also defined in `gulpfile.js`. To run a task, use `./node_modules/gulp/bin/gulp.js task-name`. Available ones are:
@ -119,7 +127,7 @@ GitHub issue tracker is reserved for bugs and other technical problems. If you d
everything, hardware is not working or have any other _support_ problem, please consult: everything, hardware is not working or have any other _support_ problem, please consult:
* [rcgroups main thread](https://www.rcgroups.com/forums/showthread.php?2495732-Cleanflight-iNav-(navigation-rewrite)-project) * [rcgroups main thread](https://www.rcgroups.com/forums/showthread.php?2495732-Cleanflight-iNav-(navigation-rewrite)-project)
* [Slack channel](https://inavflight.signup.team/) * [Telegram Group](https://t.me/INAVFlight)
## Issue trackers ## Issue trackers

File diff suppressed because it is too large Load Diff

@ -1,5 +0,0 @@
<span>1.0.2</span>
<ul>
<li>PID scaling in Configurator removed</li>
<li>Improved anonymous tracking</li>
</ul>

@ -8,6 +8,7 @@ var minimist = require('minimist');
var archiver = require('archiver'); var archiver = require('archiver');
var del = require('del'); var del = require('del');
var NwBuilder = require('nw-builder'); var NwBuilder = require('nw-builder');
var semver = require('semver');
var gulp = require('gulp'); var gulp = require('gulp');
var concat = require('gulp-concat'); var concat = require('gulp-concat');
@ -49,7 +50,9 @@ sources.css = [
'./src/css/dropdown-lists/css/style_lists.css', './src/css/dropdown-lists/css/style_lists.css',
'./js/libraries/switchery/switchery.css', './js/libraries/switchery/switchery.css',
'./js/libraries/jbox/jBox.css', './js/libraries/jbox/jBox.css',
'./node_modules/openlayers/dist/ol.css' './node_modules/openlayers/dist/ol.css',
'./src/css/logic.css',
'./src/css/defaults_dialog.css'
]; ];
sources.js = [ sources.js = [
@ -60,6 +63,8 @@ sources.js = [
'./js/libraries/d3.min.js', './js/libraries/d3.min.js',
'./js/libraries/jquery.nouislider.all.min.js', './js/libraries/jquery.nouislider.all.min.js',
'./node_modules/three/three.min.js', './node_modules/three/three.min.js',
'./js/libraries/nw-dialog.js',
'./js/libraries/bundle_xml2js.js',
'./js/libraries/Projector.js', './js/libraries/Projector.js',
'./js/libraries/CanvasRenderer.js', './js/libraries/CanvasRenderer.js',
'./js/libraries/jquery.flightindicators.js', './js/libraries/jquery.flightindicators.js',
@ -84,6 +89,7 @@ sources.js = [
'./js/serial.js', './js/serial.js',
'./js/servoMixRule.js', './js/servoMixRule.js',
'./js/motorMixRule.js', './js/motorMixRule.js',
'./js/logicCondition.js',
'./js/settings.js', './js/settings.js',
'./js/outputMapping.js', './js/outputMapping.js',
'./js/model.js', './js/model.js',
@ -95,11 +101,14 @@ sources.js = [
'./js/protocols/stm32usbdfu.js', './js/protocols/stm32usbdfu.js',
'./js/localization.js', './js/localization.js',
'./js/boards.js', './js/boards.js',
'./js/tasks.js',
'./js/servoMixerRuleCollection.js', './js/servoMixerRuleCollection.js',
'./js/motorMixerRuleCollection.js', './js/motorMixerRuleCollection.js',
'./js/logicConditionsCollection.js',
'./js/logicConditionsStatus.js',
'./js/vtx.js', './js/vtx.js',
'./main.js', './main.js',
'./js/tabs.js',
'./js/preset_definitions.js',
'./tabs/*.js', './tabs/*.js',
'./js/eventFrequencyAnalyzer.js', './js/eventFrequencyAnalyzer.js',
'./js/periodicStatusUpdater.js', './js/periodicStatusUpdater.js',
@ -108,6 +117,8 @@ sources.js = [
'./tabs/advanced_tuning.js', './tabs/advanced_tuning.js',
'./js/peripherals.js', './js/peripherals.js',
'./js/appUpdater.js', './js/appUpdater.js',
'./js/feature_framework.js',
'./js/defaults_dialog.js',
'./node_modules/openlayers/dist/ol.js' './node_modules/openlayers/dist/ol.js'
]; ];
@ -152,7 +163,7 @@ function get_task_name(key) {
} }
function getPlatforms() { function getPlatforms() {
var defaultPlatforms = ['win32', 'osx64', 'linux32', 'linux64']; var defaultPlatforms = ['win32', 'win64', 'osx64', 'linux32', 'linux64'];
var argv = minimist(process.argv.slice(2)); var argv = minimist(process.argv.slice(2));
if (argv.platform) { if (argv.platform) {
if (defaultPlatforms.indexOf(argv.platform) < 0) { if (defaultPlatforms.indexOf(argv.platform) < 0) {
@ -228,6 +239,7 @@ gulp.task('apps', gulp.series('dist', function(done) {
flavor: 'normal', flavor: 'normal',
macIcns: './images/inav.icns', macIcns: './images/inav.icns',
winIco: './images/inav.ico', winIco: './images/inav.ico',
version: get_nw_version()
}); });
builder.on('log', console.log); builder.on('log', console.log);
builder.build(function (err) { builder.build(function (err) {
@ -241,6 +253,10 @@ gulp.task('apps', gulp.series('dist', function(done) {
}); });
})); }));
function get_nw_version() {
return semver.valid(semver.coerce(require('./package.json').dependencies.nw));
}
function get_release_filename(platform, ext) { function get_release_filename(platform, ext) {
var pkg = require('./package.json'); var pkg = require('./package.json');
return 'INAV-Configurator_' + platform + '_' + pkg.version + '.' + ext; return 'INAV-Configurator_' + platform + '_' + pkg.version + '.' + ext;
@ -260,6 +276,20 @@ gulp.task('release-win32', function() {
return archive.finalize(); return archive.finalize();
}); });
gulp.task('release-win64', function() {
var pkg = require('./package.json');
var src = path.join(appsDir, pkg.name, 'win64');
var output = fs.createWriteStream(path.join(appsDir, get_release_filename('win64', 'zip')));
var archive = archiver('zip', {
zlib: { level: 9 }
});
archive.on('warning', function(err) { throw err; });
archive.on('error', function(err) { throw err; });
archive.pipe(output);
archive.directory(src, 'INAV Configurator');
return archive.finalize();
});
gulp.task('release-osx64', function() { gulp.task('release-osx64', function() {
var pkg = require('./package.json'); var pkg = require('./package.json');
var src = path.join(appsDir, pkg.name, 'osx64', pkg.name + '.app'); var src = path.join(appsDir, pkg.name, 'osx64', pkg.name + '.app');
@ -284,9 +314,10 @@ function releaseLinux(bits) {
var dirname = 'linux' + bits; var dirname = 'linux' + bits;
var pkg = require('./package.json'); var pkg = require('./package.json');
var src = path.join(appsDir, pkg.name, dirname); var src = path.join(appsDir, pkg.name, dirname);
var output = fs.createWriteStream(path.join(appsDir, get_release_filename(dirname, 'zip'))); var output = fs.createWriteStream(path.join(appsDir, get_release_filename(dirname, 'tar.gz')));
var archive = archiver('zip', { var archive = archiver('tar', {
zlib: { level: 9 } zlib: { level: 9 },
gzip: true
}); });
archive.on('warning', function(err) { throw err; }); archive.on('warning', function(err) { throw err; });
archive.on('error', function(err) { throw err; }); archive.on('error', function(err) { throw err; });

Binary file not shown.

After

Width:  |  Height:  |  Size: 4.6 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.3 KiB

@ -7,19 +7,15 @@ appUpdater.checkRelease = function (currVersion) {
$.get('https://api.github.com/repos/iNavFlight/inav-configurator/releases', function (releaseData) { $.get('https://api.github.com/repos/iNavFlight/inav-configurator/releases', function (releaseData) {
GUI.log('Loaded release information from GitHub.'); GUI.log('Loaded release information from GitHub.');
//Git return sorted list, 0 - last release //Git return sorted list, 0 - last release
if (semver.gt(releaseData[0].tag_name, currVersion)) {
GUI.log(releaseData[0].tag_name, chrome.runtime.getManifest().version);
GUI.log(currVersion);
//For download zip let newVersion = releaseData[0].tag_name;
// releaseData[0].assets.forEach(function(item, i) { let newPrerelase = releaseData[0].prerelease;
// if (str.indexOf(item.name) !== -1) {
// console.log(item); if (newPrerelase == false && semver.gt(newVersion, currVersion)) {
// downloadUrl = item.browser_download_url; GUI.log(newVersion, chrome.runtime.getManifest().version);
// } GUI.log(currVersion);
// });
GUI.log('New version aviable!'); GUI.log('New version available!');
modalStart = new jBox('Modal', { modalStart = new jBox('Modal', {
width: 400, width: 400,
height: 200, height: 200,
@ -37,4 +33,4 @@ appUpdater.checkRelease = function (currVersion) {
$('#update-notification-download').on('click', function () { $('#update-notification-download').on('click', function () {
modalStart.close(); modalStart.close();
}); });
}; };

@ -2,10 +2,6 @@
var BOARD_DEFINITIONS = [ var BOARD_DEFINITIONS = [
{ {
name: "CC3D",
identifier: "CC3D",
vcp: true
}, {
name: "ChebuzzF3", name: "ChebuzzF3",
identifier: "CHF3", identifier: "CHF3",
vcp: false vcp: false
@ -32,65 +28,30 @@ var BOARD_DEFINITIONS = [
name: "Port103R", name: "Port103R",
identifier: "103R", identifier: "103R",
vcp: false vcp: false
}, {
name: "Sparky",
identifier: "SPKY",
vcp: true
}, {
name: "STM32F3Discovery",
identifier: "SDF3",
vcp: true
}, {
name: "Colibri Race",
identifier: "CLBR",
vcp: true
}, { }, {
name: "SP Racing F3", name: "SP Racing F3",
identifier: "SRF3", identifier: "SRF3",
vcp: false vcp: false
}, {
name: "SP Racing F3 Mini",
identifier: "SRFM",
vcp: true
}, {
name: "MotoLab",
identifier: "MOTO",
vcp: true
}, {
name: "Omnibus",
identifier: "OMNI",
vcp: true
}, {
name: "Airbot F4",
identifier: "ABF4",
vcp: true
}, {
name: "Revolution",
identifier: "REVO",
vcp: true
}, {
name: "Omnibus F4",
identifier: "OBF4",
vcp: true
}, {
name: "Omnibus F4 Pro",
identifier: "OBSD",
vcp: true
} }
]; ];
var DEFAULT_BOARD_DEFINITION = { var DEFAULT_BOARD_DEFINITION = {
name: "Unknown", name: "Unknown",
identifier: "????", identifier: "????",
vcp: false vcp: true
}; };
var BOARD = { var BOARD = {
}; };
BOARD.find_board_definition = function (identifier) { BOARD.hasVcp = function (identifier) {
for (var i = 0; i < BOARD_DEFINITIONS.length; i++) { let board = BOARD.findDefinition(identifier);
var candidate = BOARD_DEFINITIONS[i]; return !!board.vcp;
}
BOARD.findDefinition = function (identifier) {
for (let i = 0; i < BOARD_DEFINITIONS.length; i++) {
let candidate = BOARD_DEFINITIONS[i];
if (candidate.identifier == identifier) { if (candidate.identifier == identifier) {
return candidate; return candidate;

@ -2,7 +2,8 @@
var CONFIGURATOR = { var CONFIGURATOR = {
// all versions are specified and compared using semantic versioning http://semver.org/ // all versions are specified and compared using semantic versioning http://semver.org/
'firmwareVersionAccepted': '1.6.0', 'minfirmwareVersionAccepted': '2.4.0',
'maxFirmwareVersionAccepted': '2.6.0', // COndition is < (lt) so we accept all in 2.2 branch, not 2.3 actualy
'connectionValid': false, 'connectionValid': false,
'connectionValidCliOnly': false, 'connectionValidCliOnly': false,
'cliActive': false, 'cliActive': false,

@ -0,0 +1,279 @@
/*global mspHelper,$,GUI,MSP,BF_CONFIG,chrome*/
'use strict';
var helper = helper || {};
helper.defaultsDialog = (function() {
let publicScope = {},
privateScope = {};
let $container;
let data = [{
"title": 'Mini Quad with 3"-7" propellers',
"settings": [
{
key: "gyro_hardware_lpf",
value: "256HZ"
},
{
key: "looptime",
value: 500
},
{
key: "gyro_lpf_hz",
value: 100
},
{
key: "gyro_lpf_type",
value: "PT1"
},
{
key: "gyro_stage2_lowpass_hz",
value: 200
},
{
key: "dterm_lpf_hz",
value: 90
},
{
key: "use_dterm_fir_filter",
value: "OFF"
},
{
key: "mc_iterm_relax_type",
value: "SETPOINT"
},
{
key: "mc_iterm_relax",
value: "RP"
},
{
key: "d_boost_factor",
value: 1.5
},
{
key: "antigravity_gain",
value: 2
},
{
key: "antigravity_accelerator",
value: 5
},
{
key: "rc_yaw_expo",
value: 70
},
{
key: "rc_expo",
value: 70
},
{
key: "roll_rate",
value: 70
},
{
key: "pitch_rate",
value: 70
},
{
key: "yaw_rate",
value: 60
},
{
key: "mc_p_pitch",
value: 44
},
{
key: "mc_i_pitch",
value: 60
},
{
key: "mc_d_pitch",
value: 25
},
{
key: "mc_p_roll",
value: 40
},
{
key: "mc_i_roll",
value: 50
},
{
key: "mc_d_roll",
value: 25
},
{
key: "mc_p_yaw",
value: 45
},
{
key: "mc_i_yaw",
value: 70
},
{
key: "mc_airmode_type",
value: "THROTTLE_THRESHOLD"
},
{
key: "applied_defaults",
value: 2
}
],
"features":[
{
bit: 5, // Enable DYNAMIC_FILTERS
state: true
}
]
},
{
"title": 'Airplane',
"id": 3,
"settings": [
{
key: "rc_yaw_expo",
value: 70
},
{
key: "rc_expo",
value: 70
},
{
key: "roll_rate",
value: 30
},
{
key: "pitch_rate",
value: 20
},
{
key: "yaw_rate",
value: 10
},
{
key: "small_angle",
value: 180
},
{
key: "applied_defaults",
value: 3
}
],
"features":[
{
bit: 4, // Enable MOTOR_STOP
state: true
}
]
},
{
"title": 'Custom UAV - INAV legacy defaults',
"settings": [
{
key: "applied_defaults",
value: 1
}
]
},
{
"title": 'Keep current settings',
"settings": [
{
key: "applied_defaults",
value: 1
}
]
}
]
publicScope.init = function() {
mspHelper.getSetting("applied_defaults").then(privateScope.onInitSettingReturned);
$container = $("#defaults-wrapper");
};
privateScope.setFeaturesBits = function (selectedDefaultPreset) {
if (selectedDefaultPreset.features && selectedDefaultPreset.features.length > 0) {
helper.features.reset();
for (const feature of selectedDefaultPreset.features) {
if (feature.state) {
helper.features.set(feature.bit);
} else {
helper.features.unset(feature.bit);
}
}
helper.features.execute(function () {
privateScope.setSettings(selectedDefaultPreset);
});
} else {
privateScope.setSettings(selectedDefaultPreset);
}
};
privateScope.setSettings = function (selectedDefaultPreset) {
Promise.mapSeries(selectedDefaultPreset.settings, function (input, ii) {
return mspHelper.getSetting(input.key);
}).then(function () {
Promise.mapSeries(selectedDefaultPreset.settings, function (input, ii) {
return mspHelper.setSetting(input.key, input.value);
}).then(function () {
mspHelper.saveToEeprom(function () {
//noinspection JSUnresolvedVariable
GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
GUI.tab_switch_cleanup(function() {
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, function () {
//noinspection JSUnresolvedVariable
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
GUI.handleReconnect();
});
});
});
})
});
};
privateScope.onPresetClick = function(event) {
$container.hide();
let selectedDefaultPreset = data[$(event.currentTarget).data("index")];
if (selectedDefaultPreset && selectedDefaultPreset.settings) {
mspHelper.loadBfConfig(function () {
privateScope.setFeaturesBits(selectedDefaultPreset)
});
}
};
privateScope.render = function() {
let $place = $container.find('.defaults-dialog__options');
$place.html("");
for (let i in data) {
if (data.hasOwnProperty(i)) {
let preset = data[i];
let $element = $("<div class='default_btn defaults_btn'>\
<a class='confirm' href='#'></a>\
</div>")
$element.find("a").html(preset.title);
$element.data("index", i).click(privateScope.onPresetClick)
$element.appendTo($place);
}
}
}
privateScope.onInitSettingReturned = function(promise) {
if (promise.value > 0) {
return; //Defaults were applied, we can just ignore
}
privateScope.render();
$container.show();
}
return publicScope;
})();

@ -19,6 +19,7 @@ var CONFIG,
SERVO_CONFIG, SERVO_CONFIG,
SERVO_RULES, SERVO_RULES,
MOTOR_RULES, MOTOR_RULES,
LOGIC_CONDITIONS,
SERIAL_CONFIG, SERIAL_CONFIG,
SENSOR_DATA, SENSOR_DATA,
MOTOR_DATA, MOTOR_DATA,
@ -29,7 +30,7 @@ var CONFIG,
ARMING_CONFIG, ARMING_CONFIG,
FC_CONFIG, FC_CONFIG,
MISC, MISC,
_3D, REVERSIBLE_MOTORS,
DATAFLASH, DATAFLASH,
SDCARD, SDCARD,
BLACKBOX, BLACKBOX,
@ -61,8 +62,11 @@ var CONFIG,
var FC = { var FC = {
MAX_SERVO_RATE: 125, MAX_SERVO_RATE: 125,
MIN_SERVO_RATE: 0, MIN_SERVO_RATE: 0,
isNewMixer: function () { isRpyFfComponentUsed: function () {
return !!(typeof CONFIG != "undefined" && semver.gte(CONFIG.flightControllerVersion, "2.0.0")); return MIXER_CONFIG.platformType == PLATFORM_AIRPLANE;
},
isRpyDComponentUsed: function () {
return MIXER_CONFIG.platformType != PLATFORM_AIRPLANE;
}, },
resetState: function () { resetState: function () {
SENSOR_STATUS = { SENSOR_STATUS = {
@ -126,11 +130,7 @@ var FC = {
}; };
PID_names = []; PID_names = [];
PIDs = new Array(10); PIDs = [];
for (var i = 0; i < 10; i++) {
PIDs[i] = new Array(3);
}
RC_MAP = []; RC_MAP = [];
// defaults // defaults
@ -168,6 +168,8 @@ var FC = {
SERVO_CONFIG = []; SERVO_CONFIG = [];
SERVO_RULES = new ServoMixerRuleCollection(); SERVO_RULES = new ServoMixerRuleCollection();
MOTOR_RULES = new MotorMixerRuleCollection(); MOTOR_RULES = new MotorMixerRuleCollection();
LOGIC_CONDITIONS = new LogicConditionsCollection();
LOGIC_CONDITIONS_STATUS = new LogicConditionsStatus();
MIXER_CONFIG = { MIXER_CONFIG = {
yawMotorDirection: 0, yawMotorDirection: 0,
@ -198,11 +200,12 @@ var FC = {
sonar: 0, sonar: 0,
air_speed: 0, air_speed: 0,
kinematics: [0.0, 0.0, 0.0], kinematics: [0.0, 0.0, 0.0],
temperature: [0, 0, 0, 0, 0, 0, 0, 0],
debug: [0, 0, 0, 0] debug: [0, 0, 0, 0]
}; };
MOTOR_DATA = new Array(8); MOTOR_DATA = new Array(8);
SERVO_DATA = new Array(8); SERVO_DATA = new Array(16);
GPS_DATA = { GPS_DATA = {
fix: 0, fix: 0,
@ -391,6 +394,9 @@ var FC = {
X: null, X: null,
Y: null, Y: null,
Z: null Z: null
},
opflow: {
Scale: null
} }
}; };
@ -409,11 +415,11 @@ var FC = {
emergencyDescentRate: null emergencyDescentRate: null
}; };
_3D = { REVERSIBLE_MOTORS = {
deadband3d_low: 0, deadband_low: 0,
deadband3d_high: 0, deadband_high: 0,
neutral3d: 0, neutral: 0,
deadband3d_throttle: 0 deadband_throttle: 0
}; };
DATAFLASH = { DATAFLASH = {
@ -538,80 +544,29 @@ var FC = {
getFeatures: function () { getFeatures: function () {
var features = [ var features = [
{bit: 1, group: 'batteryVoltage', name: 'VBAT'}, {bit: 1, group: 'batteryVoltage', name: 'VBAT'},
{bit: 4, group: 'esc', name: 'MOTOR_STOP'}, {bit: 4, group: 'other', name: 'MOTOR_STOP'},
{bit: 6, group: 'other', name: 'SOFTSERIAL', haveTip: true, showNameInTip: true}, {bit: 6, group: 'other', name: 'SOFTSERIAL', haveTip: true, showNameInTip: true},
{bit: 7, group: 'gps', name: 'GPS', haveTip: true}, {bit: 7, group: 'gps', name: 'GPS', haveTip: true},
{bit: 10, group: 'other', name: 'TELEMETRY', showNameInTip: true}, {bit: 10, group: 'other', name: 'TELEMETRY', showNameInTip: true},
{bit: 11, group: 'batteryCurrent', name: 'CURRENT_METER'}, {bit: 11, group: 'batteryCurrent', name: 'CURRENT_METER'},
{bit: 12, group: 'other', name: '3D', showNameInTip: true}, {bit: 12, group: 'other', name: 'REVERSIBLE_MOTORS', showNameInTip: true},
{bit: 15, group: 'other', name: 'RSSI_ADC', haveTip: true, showNameInTip: true}, {bit: 15, group: 'other', name: 'RSSI_ADC', haveTip: true, showNameInTip: true},
{bit: 16, group: 'other', name: 'LED_STRIP', showNameInTip: true}, {bit: 16, group: 'other', name: 'LED_STRIP', showNameInTip: true},
{bit: 17, group: 'other', name: 'DASHBOARD', showNameInTip: true}, {bit: 17, group: 'other', name: 'DASHBOARD', showNameInTip: true},
{bit: 19, group: 'other', name: 'BLACKBOX', haveTip: true, showNameInTip: true} {bit: 19, group: 'other', name: 'BLACKBOX', haveTip: true, showNameInTip: true},
{bit: 28, group: 'other', name: 'PWM_OUTPUT_ENABLE', haveTip: true},
{bit: 26, group: 'other', name: 'SOFTSPI'},
{bit: 27, group: 'other', name: 'PWM_SERVO_DRIVER', haveTip: true, showNameInTip: true},
{bit: 29, group: 'other', name: 'OSD', haveTip: false, showNameInTip: false},
{bit: 22, group: 'other', name: 'AIRMODE', haveTip: false, showNameInTip: false},
{bit: 30, group: 'other', name: 'FW_LAUNCH', haveTip: false, showNameInTip: false},
{bit: 2, group: 'other', name: 'TX_PROF_SEL', haveTip: false, showNameInTip: false},
{bit: 0, group: 'other', name: 'THR_VBAT_COMP', haveTip: true, showNameInTip: true},
{bit: 3, group: 'other', name: 'BAT_PROFILE_AUTOSWITCH', haveTip: true, showNameInTip: true}
]; ];
if (semver.lt(CONFIG.flightControllerVersion, "2.0.0")) { if (semver.gte(CONFIG.flightControllerVersion, "2.4.0") && semver.lt(CONFIG.flightControllerVersion, "2.5.0")) {
features.push( features.push({bit: 5, group: 'other', name: 'DYNAMIC_FILTERS', haveTip: true, showNameInTip: true});
{bit: 20, group: 'other', name: 'CHANNEL_FORWARDING', showNameInTip: true},
{bit: 5, group: 'other', name: 'SERVO_TILT', showNameInTip: true}
);
}
if (semver.lt(CONFIG.flightControllerVersion, "1.6.0")) {
features.push(
{bit: 2, group: 'other', name: 'INFLIGHT_ACC_CAL', showNameInTip: true},
{bit: 9, group: 'other', name: 'SONAR', showNameInTip: true},
{bit: 8, group: 'rxFailsafe', name: 'FAILSAFE'}
);
}
features.push(
{bit: 28, group: 'esc-priority', name: 'PWM_OUTPUT_ENABLE', haveTip: true}
);
/*
* Transponder disabled until not implemented in firmware
*/
if (false && semver.gte(CONFIG.apiVersion, "1.16.0")) {
features.push(
{bit: 21, group: 'other', name: 'TRANSPONDER', haveTip: true, showNameInTip: true}
);
}
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
features.push(
{bit: 26, group: 'other', name: 'SOFTSPI'}
);
}
features.push(
{bit: 27, group: 'other', name: 'PWM_SERVO_DRIVER', haveTip: true, showNameInTip: true}
);
if (semver.gte(CONFIG.flightControllerVersion, '1.5.0')) {
features.push(
{bit: 29, group: 'other', name: 'OSD', haveTip: false, showNameInTip: false}
);
}
if (semver.gte(CONFIG.flightControllerVersion, '1.7.3')) {
features.push(
{bit: 22, group: 'other', name: 'AIRMODE', haveTip: false, showNameInTip: false}
);
}
if (semver.gte(CONFIG.flightControllerVersion, '1.8.1')) {
features.push(
{bit: 30, group: 'other', name: 'FW_LAUNCH', haveTip: false, showNameInTip: false},
{bit: 2, group: 'other', name: 'TX_PROF_SEL', haveTip: false, showNameInTip: false}
);
}
if (semver.gte(CONFIG.flightControllerVersion, '2.0.0')) {
features.push(
{bit: 0, group: 'other', name: 'THR_VBAT_COMP', haveTip: true, showNameInTip: true},
{bit: 3, group: 'other', name: 'BAT_PROFILE_AUTOSWITCH', haveTip: true, showNameInTip: true}
);
} }
return features.reverse(); return features.reverse();
@ -633,7 +588,7 @@ var FC = {
getLooptimes: function () { getLooptimes: function () {
return { return {
125: { 125: {
defaultLooptime: 2000, defaultLooptime: 1000,
looptimes: { looptimes: {
4000: "250Hz", 4000: "250Hz",
3000: "334Hz", 3000: "334Hz",
@ -646,7 +601,7 @@ var FC = {
} }
}, },
1000: { 1000: {
defaultLooptime: 2000, defaultLooptime: 1000,
looptimes: { looptimes: {
4000: "250Hz", 4000: "250Hz",
2000: "500Hz", 2000: "500Hz",
@ -715,22 +670,14 @@ var FC = {
]; ];
}, },
getGpsProtocols: function () { getGpsProtocols: function () {
var data = [ return [
'NMEA', 'NMEA',
'UBLOX', 'UBLOX',
'I2C-NAV', 'I2C-NAV',
'DJI NAZA' 'DJI NAZA',
'UBLOX7',
'MTK'
]; ];
if (semver.gte(CONFIG.flightControllerVersion, "1.7.1")) {
data.push('UBLOX7')
}
if (semver.gte(CONFIG.flightControllerVersion, "1.7.2")) {
data.push('MTK')
}
return data;
}, },
getGpsBaudRates: function () { getGpsBaudRates: function () {
return [ return [
@ -751,117 +698,6 @@ var FC = {
'Disabled' 'Disabled'
]; ];
}, },
getRxTypes: function() {
// Keep value field in sync with rxReceiverType_e in rx.h
var rxTypes = [
{
name: 'RX_SERIAL',
bit: 3,
value: 3,
},
{
name: 'RX_PPM',
bit: 0,
value: 2,
},
{
name: 'RX_PWM',
bit: 13,
value: 1,
},
];
if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
rxTypes.push({
name: 'RX_SPI',
bit: 25,
value: 5,
});
}
rxTypes.push({
name: 'RX_MSP',
bit: 14,
value: 4,
});
// Versions using feature bits don't allow not having an
// RX and fallback to RX_PPM.
if (semver.gt(CONFIG.flightControllerVersion, "1.7.3")) {
rxTypes.push({
name: 'RX_NONE',
value: 0,
});
}
return rxTypes;
},
isRxTypeEnabled: function(rxType) {
if (typeof rxType === 'string') {
var types = this.getRxTypes();
for (var ii = 0; ii < types.length; ii++) {
if (types[ii].name == rxType) {
rxType = types[ii];
break;
}
}
}
if (semver.gt(CONFIG.flightControllerVersion, "1.7.3")) {
return RX_CONFIG.receiver_type == rxType.value;
}
return bit_check(BF_CONFIG.features, rxType.bit);
},
setRxTypeEnabled: function(rxType) {
if (semver.gt(CONFIG.flightControllerVersion, "1.7.3")) {
RX_CONFIG.receiver_type = rxType.value;
} else {
// Clear other rx features before
var rxTypes = this.getRxTypes();
for (var ii = 0; ii < rxTypes.length; ii++) {
BF_CONFIG.features = bit_clear(BF_CONFIG.features, rxTypes[ii].bit);
}
// Set the feature for this rx type (if any, RX_NONE is set by clearing all)
if (rxType.bit !== undefined) {
BF_CONFIG.features = bit_set(BF_CONFIG.features, rxType.bit);
}
}
},
getSerialRxTypes: function () {
var data = [
'SPEKTRUM1024',
'SPEKTRUM2048',
'SBUS',
'SUMD',
'SUMH',
'XBUS_MODE_B',
'XBUS_MODE_B_RJ01',
'IBUS'
];
if (semver.gte(CONFIG.flightControllerVersion, "1.6.0")) {
data.push('JETI EXBUS');
data.push('TBS Crossfire');
}
if (semver.gte(CONFIG.flightControllerVersion, "1.9.1")) {
data.push('FPort');
}
return data;
},
getSPIProtocolTypes: function () {
return [
'V202 250Kbps',
'V202 1Mbps',
'Syma X',
'Syma X5C',
'Cheerson CX10',
'Cheerson CX10A',
'JJRC H8_3D',
'iNav Reference protocol',
'eLeReS'
];
},
getSensorAlignments: function () { getSensorAlignments: function () {
return [ return [
'CW 0°', 'CW 0°',
@ -878,6 +714,7 @@ var FC = {
return { return {
0: { 0: {
name: "STANDARD", name: "STANDARD",
message: null,
defaultRate: 400, defaultRate: 400,
rates: { rates: {
50: "50Hz", 50: "50Hz",
@ -886,6 +723,7 @@ var FC = {
}, },
1: { 1: {
name: "ONESHOT125", name: "ONESHOT125",
message: null,
defaultRate: 1000, defaultRate: 1000,
rates: { rates: {
400: "400Hz", 400: "400Hz",
@ -895,6 +733,7 @@ var FC = {
}, },
2: { 2: {
name: "ONESHOT42", name: "ONESHOT42",
message: null,
defaultRate: 2000, defaultRate: 2000,
rates: { rates: {
400: "400Hz", 400: "400Hz",
@ -906,6 +745,7 @@ var FC = {
}, },
3: { 3: {
name: "MULTISHOT", name: "MULTISHOT",
message: null,
defaultRate: 2000, defaultRate: 2000,
rates: { rates: {
400: "400Hz", 400: "400Hz",
@ -917,6 +757,7 @@ var FC = {
}, },
4: { 4: {
name: "BRUSHED", name: "BRUSHED",
message: null,
defaultRate: 8000, defaultRate: 8000,
rates: { rates: {
8000: "8kHz", 8000: "8kHz",
@ -926,6 +767,7 @@ var FC = {
}, },
5: { 5: {
name: "DSHOT150", name: "DSHOT150",
message: null,
defaultRate: 4000, defaultRate: 4000,
rates: { rates: {
4000: "4kHz" 4000: "4kHz"
@ -933,6 +775,7 @@ var FC = {
}, },
6: { 6: {
name: "DSHOT300", name: "DSHOT300",
message: null,
defaultRate: 8000, defaultRate: 8000,
rates: { rates: {
8000: "8kHz" 8000: "8kHz"
@ -940,6 +783,7 @@ var FC = {
}, },
7: { 7: {
name: "DSHOT600", name: "DSHOT600",
message: null,
defaultRate: 16000, defaultRate: 16000,
rates: { rates: {
16000: "16kHz" 16000: "16kHz"
@ -947,10 +791,19 @@ var FC = {
}, },
8: { 8: {
name: "DSHOT1200", name: "DSHOT1200",
message: "escProtocolNotAdvised",
defaultRate: 16000, defaultRate: 16000,
rates: { rates: {
16000: "16kHz" 16000: "16kHz"
} }
},
9: {
name: "SERIALSHOT",
message: "escProtocolExperimental",
defaultRate: 4000,
rates: {
4000: "4kHz"
}
} }
}; };
}, },
@ -994,37 +847,23 @@ var FC = {
return []; return [];
}, },
getAccelerometerNames: function () { getAccelerometerNames: function () {
if (semver.gte(CONFIG.flightControllerVersion, "2.1.0")) { return [ "NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "FAKE"];
return [ "NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "FAKE"];
}
else if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
return [ "NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "FAKE"];
}
else {
return [ "NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "FAKE"];
}
}, },
getMagnetometerNames: function () { getMagnetometerNames: function () {
return ["NONE", "AUTO", "HMC5883", "AK8975", "GPSMAG", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "LIS3MDL", "FAKE"]; return ["NONE", "AUTO", "HMC5883", "AK8975", "GPSMAG", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "LIS3MDL", "FAKE"];
}, },
getBarometerNames: function () { getBarometerNames: function () {
if (semver.gte(CONFIG.flightControllerVersion, "1.6.2")) { if (semver.gte(CONFIG.flightControllerVersion, "2.4.0")) {
return ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "FAKE"]; return ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "BMP388", "FAKE"];
} } else {
else { return ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "FAKE"];
return ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "FAKE"];
} }
}, },
getPitotNames: function () { getPitotNames: function () {
if (semver.gte(CONFIG.flightControllerVersion, "1.6.3")) { return ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE"];
return ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE"];
}
else {
return ["NONE", "AUTO", "MS4525", "FAKE"];
}
}, },
getRangefinderNames: function () { getRangefinderNames: function () {
return [ "NONE", "HCSR04", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "UIB"]; return [ "NONE", "HCSR04", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "UIB", "Benewake TFmini"];
}, },
getOpticalFlowNames: function () { getOpticalFlowNames: function () {
return [ "NONE", "PMW3901", "CXOF", "MSP", "FAKE" ]; return [ "NONE", "PMW3901", "CXOF", "MSP", "FAKE" ];
@ -1065,33 +904,27 @@ var FC = {
] ]
}, },
getPidNames: function () { getPidNames: function () {
return [
if (semver.lt(CONFIG.flightControllerVersion, "1.6.0")) { 'Roll',
return PID_names; 'Pitch',
} else { 'Yaw',
return [ 'Position Z',
'Roll', 'Position XY',
'Pitch', 'Velocity XY',
'Yaw', 'Surface',
'Position Z', 'Level',
'Position XY', 'Heading',
'Velocity XY', 'Velocity Z'
'Surface', ];
'Level',
'Heading',
'Velocity Z'
];
}
}, },
getRthAltControlMode: function () { getRthAltControlMode: function () {
return ["Current", "Extra", "Fixed", "Max", "At Least"]; if (semver.gte(CONFIG.flightControllerVersion, '2.2.0'))
return ["Current", "Extra", "Fixed", "Max", "At least", "At least, linear descent"];
else
return ["Current", "Extra", "Fixed", "Max", "At least"];
}, },
getRthAllowLanding: function() { getRthAllowLanding: function() {
var values = ["Never", "Always"]; return ["Never", "Always", "Only on failsafe"];
if (semver.gt(CONFIG.flightControllerVersion, '1.7.3')) {
values.push("Only on failsafe");
}
return values;
}, },
getFailsafeProcedure: function () { getFailsafeProcedure: function () {
return { return {
@ -1102,10 +935,7 @@ var FC = {
} }
}, },
getRcMapLetters: function () { getRcMapLetters: function () {
if (semver.gte(CONFIG.flightControllerVersion, '1.9.1')) return ['A', 'E', 'R', 'T'];
return ['A', 'E', 'R', 'T'];
else
return ['A', 'E', 'R', 'T', '5', '6', '7', '8'];
}, },
isRcMapValid: function (val) { isRcMapValid: function (val) {
var strBuffer = val.split(''), var strBuffer = val.split(''),
@ -1129,10 +959,10 @@ var FC = {
}, },
getServoMixInputNames: function () { getServoMixInputNames: function () {
return [ return [
'Stabilised Roll', // 0 'Stabilized Roll', // 0
'Stabilised Pitch', // 1 'Stabilized Pitch', // 1
'Stabilised Yaw', // 2 'Stabilized Yaw', // 2
'Stabilised Throttle', // 3 'Stabilized Throttle', // 3
'RC Roll', // 4 'RC Roll', // 4
'RC Pitch', // 5 'RC Pitch', // 5
'RC Yaw', // 6 'RC Yaw', // 6
@ -1152,10 +982,17 @@ var FC = {
'RC Channel 14', // 20 'RC Channel 14', // 20
'RC Channel 15', // 21 'RC Channel 15', // 21
'RC Channel 16', // 22 'RC Channel 16', // 22
'Stabilized Roll+', // 23
'Stabilized Roll-', // 24
'Stabilized Pitch+', // 25
'Stabilized Pitch-', // 26
'Stabilized Yaw+', // 27
'Stabilized Yaw-', // 28,
'ONE' // 29,
]; ];
}, },
getServoMixInputName: function (input) { getServoMixInputName: function (input) {
return getServoMixInputNames()[input]; return this.getServoMixInputNames()[input];
}, },
getModeId: function (name) { getModeId: function (name) {
for (var i = 0; i < AUX_CONFIG.length; i++) { for (var i = 0; i < AUX_CONFIG.length; i++) {
@ -1168,6 +1005,139 @@ var FC = {
return bit_check(CONFIG.mode[Math.trunc(i / 32)], i % 32); return bit_check(CONFIG.mode[Math.trunc(i / 32)], i % 32);
}, },
isModeEnabled: function (name) { isModeEnabled: function (name) {
return FC.isModeBitSet(FC.getModeId(name)); return this.isModeBitSet(this.getModeId(name));
},
getLogicOperators: function () {
return {
0: {
name: "True",
hasOperand: [false, false]
},
1: {
name: "Equal",
hasOperand: [true, true]
},
2: {
name: "Greater Than",
hasOperand: [true, true]
},
3: {
name: "Lower Than",
hasOperand: [true, true]
},
4: {
name: "Low",
hasOperand: [true, false]
},
5: {
name: "Mid",
hasOperand: [true, false]
},
6: {
name: "High",
hasOperand: [true, false]
},
7: {
name: "AND",
hasOperand: [true, true]
},
8: {
name: "OR",
hasOperand: [true, true]
},
9: {
name: "XOR",
hasOperand: [true, true]
},
10: {
name: "NAND",
hasOperand: [true, true]
},
11: {
name: "NOR",
hasOperand: [true, true]
},
12: {
name: "NOT",
hasOperand: [true, false]
},
13: {
name: "STICKY",
hasOperand: [true, true]
}
}
},
getOperandTypes: function () {
return {
0: {
name: "Value",
type: "value",
min: -1000000,
max: 1000000,
step: 1,
default: 0
},
1: {
name: "RC Channel",
type: "range",
range: [1, 16],
default: 1
},
2: {
name: "Flight",
type: "dictionary",
default: 0,
values: {
0: "ARM timer [s]",
1: "Home distance [m]",
2: "Trip distance [m]",
3: "RSSI",
4: "Vbat [deci-Volt] [1V = 10]",
5: "Cell voltage [deci-Volt] [1V = 10]",
6: "Current [centi-Amp] [1A = 100]",
7: "Current drawn [mAh]",
8: "GPS Sats",
9: "Ground speed [cm/s]",
10: "3D speed [cm/s]",
11: "Air speed [cm/s]",
12: "Altitude [cm]",
13: "Vertical speed [cm/s]",
14: "Throttle position [%]",
15: "Roll [deg]",
16: "Pitch [deg]",
17: "Is Armed",
18: "Is Autolaunch",
19: "Is Controlling Altitude",
20: "Is Controlling Position",
21: "Is Emergency Landing",
22: "Is RTH",
23: "Is WP",
24: "Is Landing",
25: "Is Failsafe"
}
},
3: {
name: "Flight Mode",
type: "dictionary",
default: 0,
values: {
0: "Failsafe",
1: "Manual",
2: "RTH",
3: "Position Hold",
4: "Cruise",
5: "Altitude Hold",
6: "Angle",
7: "Horizon",
8: "Air"
}
},
4: {
name: "Logic Condition",
type: "range",
range: [0, 15],
default: 0
},
}
} }
}; };

@ -0,0 +1,87 @@
/*global mspHelper,BF_CONFIG*/
'use strict';
var helper = helper || {};
/*
Helper to work with FEATURES via MSP
Usage:
1. Reset everything
helper.features.reset();
2. Push feature bits you want to set
helper.features.set(5);
3. Push feature bits you want to unset
helper.features.set(8);
4. Execute and provide a callback that will be executed after MSP is done
helper.features.execute(function () {
//Do things crap over here
});
*/
helper.features = (function() {
let publicScope = {},
privateScope = {};
let toSet = [],
toUnset = [],
exitPoint;
publicScope.reset = function () {
toSet = [];
toUnset = [];
};
publicScope.set = function (bit) {
toSet.push(bit);
};
publicScope.unset = function (bit) {
toUnset.push(bit);
};
publicScope.updateUI = function ($container, values) {
$container.find('[data-bit].feature').each(function () {
let $this = $(this);
$this.prop('checked', bit_check(values, $this.attr("data-bit")));
});
};
publicScope.fromUI = function ($container) {
$container.find('[data-bit].feature').each(function () {
let $this = $(this);
if ($this.is(":checked")) {
publicScope.set($this.attr("data-bit"));
} else {
publicScope.unset($this.attr("data-bit"));
}
});
};
publicScope.execute = function(callback) {
exitPoint = callback;
mspHelper.loadBfConfig(privateScope.setBits);
};
privateScope.setBits = function () {
for (const bit of toSet) {
BF_CONFIG.features = bit_set(BF_CONFIG.features, bit);
}
for (const bit of toUnset) {
BF_CONFIG.features = bit_clear(BF_CONFIG.features, bit);
}
mspHelper.saveBfConfig(exitPoint);
}
return publicScope;
})();

@ -4,7 +4,6 @@
var TABS = {}; // filled by individual tab js file var TABS = {}; // filled by individual tab js file
var GUI_control = function () { var GUI_control = function () {
this.auto_connect = false;
this.connecting_to = false; this.connecting_to = false;
this.connected_to = false; this.connected_to = false;
this.connect_lock = false; this.connect_lock = false;
@ -14,6 +13,7 @@ var GUI_control = function () {
this.defaultAllowedTabsWhenDisconnected = [ this.defaultAllowedTabsWhenDisconnected = [
'landing', 'landing',
'firmware_flasher', 'firmware_flasher',
'mission_control',
'help' 'help'
]; ];
this.defaultAllowedTabsWhenConnected = [ this.defaultAllowedTabsWhenConnected = [
@ -28,12 +28,11 @@ var GUI_control = function () {
'logging', 'logging',
'onboard_logging', 'onboard_logging',
'modes', 'modes',
'motors', 'outputs',
'pid_tuning', 'pid_tuning',
'ports', 'ports',
'receiver', 'receiver',
'sensors', 'sensors',
'servos',
'calibration', 'calibration',
'setup', 'setup',
'osd', 'osd',
@ -129,7 +128,7 @@ GUI_control.prototype.switchery = function() {
GUI_control.prototype.content_ready = function (callback) { GUI_control.prototype.content_ready = function (callback) {
const content = $('#content').removeClass('loading');
$('.togglesmall').each(function(index, elem) { $('.togglesmall').each(function(index, elem) {
var switchery = new Switchery(elem, { var switchery = new Switchery(elem, {
size: 'small', size: 'small',
@ -191,7 +190,13 @@ GUI_control.prototype.content_ready = function (callback) {
}); });
}); });
if (callback) callback(); const duration = content.data('empty') ? 0 : 400;
$('#content .data-loading').fadeOut(duration, function() {
$(this).remove();
});
if (callback) {
callback();
}
}; };
GUI_control.prototype.updateStatusBar = function() { GUI_control.prototype.updateStatusBar = function() {
@ -244,5 +249,15 @@ GUI_control.prototype.simpleBind = function () {
}); });
}; };
GUI_control.prototype.load = function(rel, callback) {
const content = $('#content').addClass('loading');
$.get(rel, function(data) {
$(data).appendTo(content);
if (callback) {
callback();
}
});
}
// initialize object into GUI variable // initialize object into GUI variable
var GUI = new GUI_control(); var GUI = new GUI_control();

@ -101,4 +101,15 @@ DataView.prototype.readString = function() {
s += String.fromCharCode(c); s += String.fromCharCode(c);
} }
return s; return s;
}; };
DataView.prototype.asHex = function() {
let s = "";
for (let ii = 0; ii < this.byteLength; ii++) {
if (ii == this.offset) {
s += "/"
}
s += this.getUint8(ii).toString(16);
}
return s;
};

File diff suppressed because it is too large Load Diff

@ -0,0 +1,125 @@
'use strict';
var nwdialog = {
_context: (typeof global === 'undefined' || typeof global.DOMDocument === 'undefined') ? document : global.DOMDocument,
setContext: function(context) {
this._context = context;
},
openFileDialog: function(filter, multiple, workdir, callback) {
var fn = callback;
var node = this._context.createElement('input');
node.type = 'file';
node.id = 'open-file-dialog';
node.style = 'display: none';
if (typeof filter === 'function') {
fn = filter;
} else if (typeof filter === 'string') {
node.setAttribute('accept', filter);
} else if (typeof filter === 'boolean' && filter === true) {
node.setAttribute('multiple', '');
} else if (this.isArray(filter)) {
node.setAttribute('accept', filter.join(','));
}
if (typeof multiple === 'function') {
fn = multiple;
} else if (typeof multiple === 'string') {
node.setAttribute('nwworkingdir', multiple);
} else if (typeof multiple === 'boolean' && multiple === true) {
node.setAttribute('multiple', '');
}
if (typeof workdir === 'function') {
fn = workdir;
} else if (typeof workdir === 'string') {
node.setAttribute('nwworkingdir', workdir);
}
this._context.body.appendChild(node);
node.addEventListener('change', function(e) {
fn(node.value);
node.remove();
});
node.click();
},
saveFileDialog: function(name, accept, directory, callback) {
var fn = callback;
var node = this._context.createElement('input');
node.type = 'file';
node.id = 'save-file-dialog';
node.style = 'display: none';
node.setAttribute('nwsaveas', '');
if (typeof name === 'function') {
fn = name;
} else if (typeof name === 'string') {
node.setAttribute('nwsaveas', name);
}
if (typeof accept === 'function') {
fn = accept;
} else if (typeof accept === 'string') {
node.setAttribute('accept', accept);
} else if (this.isArray(accept)) {
node.setAttribute('accept', accept.join(','));
}
if (typeof directory === 'function') {
fn = directory;
} else if (typeof directory === 'string') {
node.setAttribute('nwworkingdir', directory);
}
this._context.body.appendChild(node);
node.addEventListener('change', function() {
fn(node.value);
node.remove();
});
node.click();
},
folderBrowserDialog: function(workdir, callback) {
var fn = callback;
var node = this._context.createElement('input');
node.type = 'file';
node.id = 'folder-browser-dialog';
node.style = 'display: none';
node.nwdirectory= true;
if (typeof workdir === 'function') {
fn = workdir
} else if (typeof workdir === 'string') {
node.setAttribute('nwworkingdir', workdir);
}
this._context.body.appendChild(node);
node.addEventListener('change', function() {
fn(node.value);
node.remove();
});
node.click();
},
isArray: function(value) {
return Object.prototype.toString.call(value) === '[object Array]';
}
}
if (typeof nw !== 'undefined') {
if (typeof exports == 'undefined') {
nw.Dialog = nwdialog;
window.dialog = nwdialog;
} else {
module.exports = nwdialog;
}
}

@ -19,8 +19,12 @@ function localize() {
$('[data-i18n]:not(.i18n-replaced)').each(function() { $('[data-i18n]:not(.i18n-replaced)').each(function() {
var element = $(this); var element = $(this);
element.html(translate(element.data('i18n'))); const translated = translate(element.data('i18n'));
element.html(translated);
element.addClass('i18n-replaced'); element.addClass('i18n-replaced');
if (element.attr("title") !== "") {
element.attr("title", translated);
}
}); });
$('[i18n_title]:not(.i18n_title-replaced)').each(function() { $('[i18n_title]:not(.i18n_title-replaced)').each(function() {
@ -52,4 +56,4 @@ function localize() {
}); });
return localized; return localized;
} }

@ -0,0 +1,253 @@
/*global $,FC*/
'use strict';
let LogicCondition = function (enabled, operation, operandAType, operandAValue, operandBType, operandBValue, flags) {
let self = {};
let $row;
self.getEnabled = function () {
return !!enabled;
};
self.setEnabled = function (data) {
enabled = !!data;
};
self.getOperation = function () {
return operation;
};
self.setOperation = function (data) {
operation = data;
};
self.getOperandAType = function () {
return operandAType;
};
self.setOperandAType = function (data) {
operandAType = data;
};
self.getOperandAValue = function () {
return operandAValue;
};
self.setOperandAValue = function (data) {
operandAValue = data;
};
self.getOperandBType = function () {
return operandBType;
};
self.setOperandBType = function (data) {
operandBType = data;
};
self.getOperandBValue = function () {
return operandBValue;
};
self.setOperandBValue = function (data) {
operandBValue = data;
};
self.getFlags = function () {
return flags;
};
self.setFlags = function (data) {
flags = data;
};
self.onEnabledChange = function (event) {
let $cT = $(event.currentTarget);
self.setEnabled(!!$cT.prop('checked'));
};
self.getOperatorMetadata = function () {
return FC.getLogicOperators()[self.getOperation()];
};
self.hasOperand = function (val) {
return self.getOperatorMetadata().hasOperand[val];
};
self.onOperatorChange = function (event) {
let $cT = $(event.currentTarget);
self.setOperation($cT.val());
self.setOperandAType(0);
self.setOperandBType(0);
self.setOperandAValue(0);
self.setOperandBValue(0);
self.renderOperand(0);
self.renderOperand(1);
};
self.onOperatorTypeChange = function (event) {
let $cT = $(event.currentTarget),
operand = $cT.data("operand"),
$container = $cT.parent(),
operandMetadata = FC.getOperandTypes()[$cT.val()];
if (operand == 0) {
self.setOperandAType($cT.val());
self.setOperandAValue(operandMetadata.default);
} else {
self.setOperandBType($cT.val());
self.setOperandBValue(operandMetadata.default);
}
self.renderOperandValue($container, operandMetadata, operand, operandMetadata.default);
};
self.onOperatorValueChange = function (event) {
let $cT = $(event.currentTarget),
operand = $cT.data("operand");
if (operand == 0) {
self.setOperandAValue($cT.val());
} else {
self.setOperandBValue($cT.val());
}
};
self.renderOperandValue = function ($container, operandMetadata, operand, value) {
$container.find('.logic_element__operand--value').remove();
switch (operandMetadata.type) {
case "value":
$container.append('<input type="number" class="logic_element__operand--value" data-operand="' + operand + '" step="' + operandMetadata.step + '" min="' + operandMetadata.min + '" max="' + operandMetadata.max + '" value="' + value + '" />');
break;
case "range":
case "dictionary":
$container.append('<select class="logic_element__operand--value" data-operand="' + operand + '"></select>');
let $t = $container.find('.logic_element__operand--value');
if (operandMetadata.type == "range") {
for (let i = operandMetadata.range[0]; i <= operandMetadata.range[1]; i++) {
$t.append('<option value="' + i + '">' + i + '</option>');
}
} else if (operandMetadata.type == "dictionary") {
for (let k in operandMetadata.values) {
if (operandMetadata.values.hasOwnProperty(k)) {
$t.append('<option value="' + k + '">' + operandMetadata.values[k] + '</option>');
}
}
}
$t.val(value);
break;
}
$container.find('.logic_element__operand--value').change(self.onOperatorValueChange);
};
self.renderOperand = function (operand) {
let type, value, $container;
if (operand == 0) {
type = operandAType;
value = operandAValue;
$container = $row.find('.logic_cell__operandA');
} else {
type = operandBType;
value = operandBValue;
$container = $row.find('.logic_cell__operandB');
}
$container.html('');
if (self.hasOperand(operand)) {
$container.append('<select class="logic_element__operand--type" data-operand="' + operand + '"></select>');
let $t = $container.find('.logic_element__operand--type');
for (let k in FC.getOperandTypes()) {
if (FC.getOperandTypes().hasOwnProperty(k)) {
let op = FC.getOperandTypes()[k];
if (type == k) {
$t.append('<option value="' + k + '" selected>' + op.name + '</option>');
/*
* Render value element depending on type
*/
self.renderOperandValue($container, op, operand, value);
} else {
$t.append('<option value="' + k + '">' + op.name + '</option>');
}
}
}
/*
* Bind events
*/
$t.change(self.onOperatorTypeChange);
}
}
self.update = function (index, value, $container) {
if (typeof $row === 'undefined') {
return;
}
let $marker = $row.find('.logic_cell__active_marker');
if (!!value) {
$marker.addClass("logic_cell__active_marker--active");
$marker.removeClass("logic_cell__active_marker--inactive");
} else {
$marker.removeClass("logic_cell__active_marker--active");
$marker.addClass("logic_cell__active_marker--inactive");
}
}
self.render = function (index, $container) {
$container.find('tbody').append('<tr>\
<td class="logic_cell__index"></td>\
<td class="logic_cell__enabled"></td>\
<td class="logic_cell__operation"></td>\
<td class="logic_cell__operandA"></td>\
<td class="logic_cell__operandB"></td>\
<td class="logic_cell__flags"><div class="logic_cell__active_marker"></div></td>\
</tr>\
');
$row = $container.find('tr:last');
$row.find('.logic_cell__index').html(index);
$row.find('.logic_cell__enabled').html("<input type='checkbox' class='toggle logic_element__enabled' />");
$row.find('.logic_element__enabled').
prop('checked', self.getEnabled()).
change(self.onEnabledChange);
/*
* Operator select
*/
$row.find('.logic_cell__operation').html("<select class='logic_element__operation' ></select>");
let $t = $row.find('.logic_element__operation');
for (let k in FC.getLogicOperators()) {
if (FC.getLogicOperators().hasOwnProperty(k)) {
let o = FC.getLogicOperators()[k];
if (self.getOperation() == parseInt(k, 10)) {
$t.append('<option value="' + k + '" selected>' + o.name + '</option>');
} else {
$t.append('<option value="' + k + '">' + o.name + '</option>');
}
}
}
$t.change(self.onOperatorChange);
self.renderOperand(0);
self.renderOperand(1);
}
return self;
};

@ -0,0 +1,87 @@
'use strict';
let LogicConditionsCollection = function () {
let self = {},
data = [],
$container;
self.put = function (element) {
data.push(element);
};
self.get = function () {
return data;
};
self.flush = function () {
data = [];
};
self.getCount = function () {
return data.length
};
self.open = function () {
if (semver.lt(CONFIG.flightControllerVersion, "2.2.0")) {
return;
}
self.render();
$container.show();
};
self.render = function () {
let $table = $container.find(".logic__table")
$table.find("tbody tr").remove();
for (let k in self.get()) {
if (self.get().hasOwnProperty(k)) {
self.get()[k].render(k, $table);
}
}
GUI.switchery();
};
self.onSave = function () {
let chain = new MSPChainerClass()
chain.setChain([
mspHelper.sendLogicConditions,
mspHelper.saveToEeprom
]);
chain.execute();
};
self.onClose = function() {
$container.hide();
};
self.init = function ($element) {
if (semver.lt(CONFIG.flightControllerVersion, "2.2.0")) {
return;
}
$container = $element;
$container.find('.logic__save').click(self.onSave);
$container.find('.logic__close').click(self.onClose);
};
self.update = function(statuses) {
let $table = $container.find(".logic__table")
for (let k in self.get()) {
if (self.get().hasOwnProperty(k)) {
self.get()[k].update(k, statuses.get(k), $table);
}
}
}
return self;
};

@ -0,0 +1,25 @@
'use strict';
let LogicConditionsStatus = function () {
let self = {},
data = [];
self.set = function (condition, value) {
data[condition] = value;
}
self.get = function (condition) {
if (typeof data[condition] !== 'undefined') {
return data[condition];
} else {
return null;
}
}
self.getAll = function() {
return data;
}
return self;
};

@ -517,7 +517,53 @@ const mixerList = [
new ServoMixRule(3, INPUT_STABILIZED_YAW, 50, 0), new ServoMixRule(3, INPUT_STABILIZED_YAW, 50, 0),
new ServoMixRule(4, INPUT_STABILIZED_YAW, 50, 0), new ServoMixRule(4, INPUT_STABILIZED_YAW, 50, 0),
] ]
} },
{
id: 31,
name: 'Rover',
model: 'custom',
image: 'custom',
enabled: true,
legacy: false,
platform: PLATFORM_ROVER,
motorMixer: [
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
],
servoMixer: [
new ServoMixRule(3, INPUT_STABILIZED_YAW, 100, 0),
]
},
{
id: 32,
name: 'Boat',
model: 'custom',
image: 'custom',
enabled: true,
legacy: false,
platform: PLATFORM_BOAT,
motorMixer: [
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
],
servoMixer: [
new ServoMixRule(3, INPUT_STABILIZED_YAW, 100, 0),
]
}
,
{
id: 33,
name: 'Other',
model: 'custom',
image: 'custom',
enabled: true,
legacy: false,
platform: PLATFORM_OTHER,
motorMixer: [
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
],
servoMixer: [
new ServoMixRule(3, INPUT_STABILIZED_YAW, 100, 0),
]
}
]; ];
const platformList = [ const platformList = [
@ -548,19 +594,19 @@ const platformList = [
{ {
id: 4, id: 4,
name: "Rover", name: "Rover",
enabled: false, enabled: true,
flapsPossible: false flapsPossible: false
}, },
{ {
id: 5, id: 5,
name: "Boat", name: "Boat",
enabled: false, enabled: true,
flapsPossible: false flapsPossible: false
}, },
{ {
id: 6, id: 6,
name: "Other", name: "Other",
enabled: false, enabled: true,
flapsPossible: false flapsPossible: false
} }
]; ];

@ -194,5 +194,23 @@ var MSPCodes = {
MSP2_INAV_SELECT_BATTERY_PROFILE: 0x2018, MSP2_INAV_SELECT_BATTERY_PROFILE: 0x2018,
MSP2_INAV_DEBUG: 0x2019 MSP2_INAV_DEBUG: 0x2019,
MSP2_BLACKBOX_CONFIG: 0x201A,
MSP2_SET_BLACKBOX_CONFIG: 0x201B,
MSP2_INAV_TEMP_SENSOR_CONFIG: 0x201C,
MSP2_INAV_SET_TEMP_SENSOR_CONFIG: 0x201D,
MSP2_INAV_TEMPERATURES: 0x201E,
MSP2_INAV_SERVO_MIXER: 0x2020,
MSP2_INAV_SET_SERVO_MIXER: 0x2021,
MSP2_INAV_LOGIC_CONDITIONS: 0x2022,
MSP2_INAV_SET_LOGIC_CONDITIONS: 0x2023,
MSP2_INAV_LOGIC_CONDITIONS_STATUS: 0x2026,
MSP2_PID: 0x2030,
MSP2_SET_PID: 0x2031,
MSP2_INAV_OPFLOW_CALIBRATION: 0x2032
}; };

File diff suppressed because it is too large Load Diff

@ -16,6 +16,66 @@ let OutputMappingCollection = function () {
const TIM_USE_LED = 24; const TIM_USE_LED = 24;
const TIM_USE_BEEPER = 25; const TIM_USE_BEEPER = 25;
const OUTPUT_TYPE_MOTOR = 0;
const OUTPUT_TYPE_SERVO = 1;
function getTimerMap(isMR, motors, servos) {
let timerMap = [],
motorsToGo = motors,
servosToGo = servos;
for (let i = 0; i < data.length; i++) {
timerMap[i] = null;
if (isMR) {
if (servosToGo > 0 && bit_check(data[i], TIM_USE_MC_SERVO)) {
servosToGo--;
timerMap[i] = OUTPUT_TYPE_SERVO;
} else if (motorsToGo > 0 && bit_check(data[i], TIM_USE_MC_MOTOR)) {
motorsToGo--;
timerMap[i] = OUTPUT_TYPE_MOTOR;
}
} else {
if (servosToGo > 0 && bit_check(data[i], TIM_USE_FW_SERVO)) {
servosToGo--;
timerMap[i] = OUTPUT_TYPE_SERVO;
} else if (motorsToGo > 0 && bit_check(data[i], TIM_USE_FW_MOTOR)) {
motorsToGo--;
timerMap[i] = OUTPUT_TYPE_MOTOR;
}
}
}
return timerMap;
};
self.getOutputTable = function (isMR, motors, servos) {
let currentMotorIndex = 1,
currentServoIndex = 0,
timerMap = getTimerMap(isMR, motors, servos.length),
outputMap = [],
offset = getFirstOutputOffset();
for (let i = 0; i < self.getOutputCount(); i++) {
let assignment = timerMap[i + offset];
if (assignment === null) {
outputMap[i] = "-";
} else if (assignment == OUTPUT_TYPE_MOTOR) {
outputMap[i] = "Motor " + currentMotorIndex;
currentMotorIndex++;
} else if (assignment == OUTPUT_TYPE_SERVO) {
outputMap[i] = "Servo " + servos[currentServoIndex];
currentServoIndex++;
}
}
return outputMap;
};
self.flush = function () { self.flush = function () {
data = []; data = [];
}; };
@ -78,14 +138,6 @@ let OutputMappingCollection = function () {
return getOutput(servoIndex, TIM_USE_FW_SERVO); return getOutput(servoIndex, TIM_USE_FW_SERVO);
}; };
self.getFwMotorOutput = function (index) {
return getOutput(index, TIM_USE_FW_MOTOR);
};
self.getMrMotorOutput = function (index) {
return getOutput(index, TIM_USE_MC_MOTOR);
};
self.getMrServoOutput = function (index) { self.getMrServoOutput = function (index) {
return getOutput(index, TIM_USE_MC_SERVO); return getOutput(index, TIM_USE_MC_SERVO);
}; };

@ -19,15 +19,11 @@ helper.periodicStatusUpdater = (function () {
} }
if (baudSpeed >= 115200) { if (baudSpeed >= 115200) {
return 200; return 300;
} else if (baudSpeed >= 57600) { } else if (baudSpeed >= 57600) {
return 400;
} else if (baudSpeed >= 38400) {
return 500;
} else if (baudSpeed >= 19200) {
return 600; return 600;
} else if (baudSpeed >= 9600) { } else if (baudSpeed >= 38400) {
return 750; return 800;
} else { } else {
return 1000; return 1000;
} }
@ -57,30 +53,16 @@ helper.periodicStatusUpdater = (function () {
if (ANALOG != undefined) { if (ANALOG != undefined) {
var nbCells; var nbCells;
if (semver.gte(CONFIG.flightControllerVersion, '1.8.1')) { nbCells = ANALOG.cell_count;
nbCells = ANALOG.cell_count;
} else {
nbCells = Math.floor(ANALOG.voltage / MISC.vbatmaxcellvoltage) + 1;
if (ANALOG.voltage == 0)
nbCells = 1;
}
var min = MISC.vbatmincellvoltage * nbCells; var min = MISC.vbatmincellvoltage * nbCells;
var max = MISC.vbatmaxcellvoltage * nbCells; var max = MISC.vbatmaxcellvoltage * nbCells;
var warn = MISC.vbatwarningcellvoltage * nbCells; var warn = MISC.vbatwarningcellvoltage * nbCells;
if (semver.gte(CONFIG.flightControllerVersion, '1.8.1')) { $(".battery-status").css({
$(".battery-status").css({ width: ANALOG.battery_percentage + "%",
width: ANALOG.battery_percentage + "%", display: 'inline-block'
display: 'inline-block' });
});
} else {
$(".battery-status").css({
width: ((ANALOG.voltage - min) / (max - min) * 100) + "%",
display: 'inline-block'
});
}
if (active) { if (active) {
$(".linkicon").css({ $(".linkicon").css({
'background-image': 'url("../images/icons/cf_icon_link_active.svg")' 'background-image': 'url("../images/icons/cf_icon_link_active.svg")'
@ -91,7 +73,7 @@ helper.periodicStatusUpdater = (function () {
}); });
} }
if (((semver.gte(CONFIG.flightControllerVersion, '1.8.1')) && (((ANALOG.use_capacity_thresholds) && (ANALOG.battery_remaining_capacity <= (MISC.battery_capacity_warning - MISC.battery_capacity_critical))) || ((!ANALOG.use_capacity_thresholds) && (ANALOG.voltage < warn))) || (ANALOG.voltage < min)) || ((semver.lt(CONFIG.flightControllerVersion, '1.8.1')) && (ANALOG.voltage < warn))) { if (((ANALOG.use_capacity_thresholds && ANALOG.battery_remaining_capacity <= MISC.battery_capacity_warning - MISC.battery_capacity_critical) || (!ANALOG.use_capacity_thresholds && ANALOG.voltage < warn)) || ANALOG.voltage < min) {
$(".battery-status").css('background-color', '#D42133'); $(".battery-status").css('background-color', '#D42133');
} else { } else {
$(".battery-status").css('background-color', '#59AA29'); $(".battery-status").css('background-color', '#59AA29');
@ -119,23 +101,10 @@ helper.periodicStatusUpdater = (function () {
return; return;
} }
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) { MSP.send_message(MSPCodes.MSP_SENSOR_STATUS, false, false);
MSP.send_message(MSPCodes.MSP_SENSOR_STATUS, false, false); MSP.send_message(MSPCodes.MSPV2_INAV_STATUS, false, false);
}
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
MSP.send_message(MSPCodes.MSPV2_INAV_STATUS, false, false);
} else {
MSP.send_message(MSPCodes.MSP_STATUS_EX, false, false);
}
MSP.send_message(MSPCodes.MSP_ACTIVEBOXES, false, false); MSP.send_message(MSPCodes.MSP_ACTIVEBOXES, false, false);
MSP.send_message(MSPCodes.MSPV2_INAV_ANALOG, false, false);
if (semver.gte(CONFIG.flightControllerVersion, '1.8.1')) {
MSP.send_message(MSPCodes.MSPV2_INAV_ANALOG, false, false);
} else {
MSP.send_message(MSPCodes.MSP_ANALOG, false, false);
}
privateScope.updateView(); privateScope.updateView();
} }

@ -121,16 +121,6 @@ PortHandler.check = function () {
$('div#port-picker #port').val(GUI.connected_to); $('div#port-picker #port').val(GUI.connected_to);
} }
// start connect procedure (if statement is valid)
if (GUI.auto_connect && !GUI.connecting_to && !GUI.connected_to) {
// we need firmware flasher protection over here
if (GUI.active_tab != 'firmware_flasher') {
helper.timeout.add('auto-connect_timeout', function () {
$('div#port-picker a.connect').click();
}, 100); // timeout so bus have time to initialize after being detected by the system
}
}
// trigger callbacks // trigger callbacks
for (var i = (self.port_detected_callbacks.length - 1); i >= 0; i--) { for (var i = (self.port_detected_callbacks.length - 1); i >= 0; i--) {
var obj = self.port_detected_callbacks[i]; var obj = self.port_detected_callbacks[i];

File diff suppressed because it is too large Load Diff

@ -100,25 +100,45 @@ STM32_protocol.prototype.connect = function (port, baud, hex, options, callback)
serial.send(bufferOut, function () { serial.send(bufferOut, function () {
serial.disconnect(function (result) { serial.disconnect(function (result) {
if (result) { if (result) {
// delay to allow board to boot in bootloader mode var intervalMs = 200;
// required to detect if a DFU device appears var retries = 0;
setTimeout(function() { var maxRetries = 50; // timeout after intervalMs * 50
// refresh device list var interval = setInterval(function() {
var tryFailed = function() {
retries++;
if (retries > maxRetries) {
clearInterval(interval);
GUI.log('<span style="color: red">Failed</span> to flash ' + port);
}
}
// Check for DFU devices
PortHandler.check_usb_devices(function(dfu_available) { PortHandler.check_usb_devices(function(dfu_available) {
if(dfu_available) { if (dfu_available) {
clearInterval(interval);
STM32DFU.connect(usbDevices.STM32DFU, hex, options); STM32DFU.connect(usbDevices.STM32DFU, hex, options);
} else { return;
serial.connect(port, {bitrate: self.baud, parityBit: 'even', stopBits: 'one'}, function (openInfo) {
if (openInfo) {
self.initialize();
} else {
GUI.connect_lock = false;
GUI.log('<span style="color: red">Failed</span> to open serial port');
}
});
} }
// Check for the serial port
serial.getDevices(function(devices) {
if (devices && devices.includes(port)) {
// Serial port might briefly reappear on DFU devices while
// the FC is rebooting, so we don't clear the interval
// until we succesfully connect.
serial.connect(port, {bitrate: self.baud, parityBit: 'even', stopBits: 'one'}, function (openInfo) {
if (openInfo) {
clearInterval(interval);
self.initialize();
} else {
GUI.connect_lock = false;
tryFailed();
}
});
return;
}
tryFailed();
});
}); });
}, 1000); }, intervalMs);
} else { } else {
GUI.connect_lock = false; GUI.connect_lock = false;
} }

@ -300,9 +300,9 @@ var serial = {
*/ */
getTimeout: function () { getTimeout: function () {
if (serial.bitrate >= 57600) { if (serial.bitrate >= 57600) {
return 1500; return 3000;
} else { } else {
return 2500; return 4000;
} }
} }

@ -22,7 +22,18 @@ $(document).ready(function () {
GUI.handleReconnect = function ($tabElement) { GUI.handleReconnect = function ($tabElement) {
if (BOARD.find_board_definition(CONFIG.boardIdentifier).vcp) { // VCP-based flight controls may crash old drivers, we catch and reconnect let modal;
if (BOARD.hasVcp(CONFIG.boardIdentifier)) { // VCP-based flight controls may crash old drivers, we catch and reconnect
modal = new jBox('Modal', {
width: 400,
height: 100,
animation: false,
closeOnClick: false,
closeOnEsc: false,
content: $('#modal-reconnect')
}).open();
/* /*
Disconnect Disconnect
@ -35,6 +46,7 @@ $(document).ready(function () {
Connect again Connect again
*/ */
setTimeout(function start_connection() { setTimeout(function start_connection() {
modal.close();
$('a.connect').click(); $('a.connect').click();
/* /*
@ -46,7 +58,7 @@ $(document).ready(function () {
}, 500); }, 500);
} }
}, 5000); }, 7000);
} else { } else {
helper.timeout.add('waiting_for_bootup', function waiting_for_bootup() { helper.timeout.add('waiting_for_bootup', function waiting_for_bootup() {
@ -141,9 +153,7 @@ $(document).ready(function () {
// unlock port select & baud // unlock port select & baud
$port.prop('disabled', false); $port.prop('disabled', false);
if (!GUI.auto_connect) { $baud.prop('disabled', false);
$baud.prop('disabled', false);
}
// reset connect / disconnect button // reset connect / disconnect button
$('div.connect_controls a.connect').removeClass('active'); $('div.connect_controls a.connect').removeClass('active');
@ -165,45 +175,6 @@ $(document).ready(function () {
} }
}); });
// auto-connect
chrome.storage.local.get('auto_connect', function (result) {
if (result.auto_connect === 'undefined' || result.auto_connect) {
// default or enabled by user
GUI.auto_connect = true;
$('input.auto_connect').prop('checked', true);
$('input.auto_connect, span.auto_connect').prop('title', chrome.i18n.getMessage('autoConnectEnabled'));
$baud.val(115200).prop('disabled', true);
} else {
// disabled by user
GUI.auto_connect = false;
$('input.auto_connect').prop('checked', false);
$('input.auto_connect, span.auto_connect').prop('title', chrome.i18n.getMessage('autoConnectDisabled'));
}
// bind UI hook to auto-connect checkbos
$('input.auto_connect').change(function () {
GUI.auto_connect = $(this).is(':checked');
// update title/tooltip
if (GUI.auto_connect) {
$('input.auto_connect, span.auto_connect').prop('title', chrome.i18n.getMessage('autoConnectEnabled'));
$baud.val(115200).prop('disabled', true);
} else {
$('input.auto_connect, span.auto_connect').prop('title', chrome.i18n.getMessage('autoConnectDisabled'));
if (!GUI.connected_to && !GUI.connecting_to) $('select#baud').prop('disabled', false);
}
chrome.storage.local.set({'auto_connect': GUI.auto_connect});
});
});
PortHandler.initialize(); PortHandler.initialize();
}); });
@ -228,6 +199,10 @@ function onValidFirmware()
GUI.allowedTabs = GUI.defaultAllowedTabsWhenConnected.slice(); GUI.allowedTabs = GUI.defaultAllowedTabsWhenConnected.slice();
onConnect(); onConnect();
if (semver.gte(CONFIG.flightControllerVersion, "2.3.0")) {
helper.defaultsDialog.init();
}
$('#tabs ul.mode-connected .tab_setup a').click(); $('#tabs ul.mode-connected .tab_setup a').click();
}); });
}); });
@ -245,7 +220,7 @@ function onInvalidFirmwareVariant()
function onInvalidFirmwareVersion() function onInvalidFirmwareVersion()
{ {
GUI.log(chrome.i18n.getMessage('firmwareVersionNotSupported', [CONFIGURATOR.firmwareVersionAccepted])); GUI.log(chrome.i18n.getMessage('firmwareVersionNotSupported', [CONFIGURATOR.minfirmwareVersionAccepted, CONFIGURATOR.maxFirmwareVersionAccepted]));
CONFIGURATOR.connectionValid = true; // making it possible to open the CLI tab CONFIGURATOR.connectionValid = true; // making it possible to open the CLI tab
GUI.allowedTabs = ['cli']; GUI.allowedTabs = ['cli'];
onConnect(); onConnect();
@ -305,7 +280,7 @@ function onOpen(openInfo) {
MSP.send_message(MSPCodes.MSP_FC_VERSION, false, false, function () { MSP.send_message(MSPCodes.MSP_FC_VERSION, false, false, function () {
googleAnalytics.sendEvent('Firmware', 'Variant', CONFIG.flightControllerIdentifier + ',' + CONFIG.flightControllerVersion); googleAnalytics.sendEvent('Firmware', 'Variant', CONFIG.flightControllerIdentifier + ',' + CONFIG.flightControllerVersion);
GUI.log(chrome.i18n.getMessage('fcInfoReceived', [CONFIG.flightControllerIdentifier, CONFIG.flightControllerVersion])); GUI.log(chrome.i18n.getMessage('fcInfoReceived', [CONFIG.flightControllerIdentifier, CONFIG.flightControllerVersion]));
if (semver.gte(CONFIG.flightControllerVersion, CONFIGURATOR.firmwareVersionAccepted)) { if (semver.gte(CONFIG.flightControllerVersion, CONFIGURATOR.minfirmwareVersionAccepted) && semver.lt(CONFIG.flightControllerVersion, CONFIGURATOR.maxFirmwareVersionAccepted)) {
mspHelper.getCraftName(function(name) { mspHelper.getCraftName(function(name) {
if (name) { if (name) {
CONFIG.name = name; CONFIG.name = name;
@ -356,6 +331,19 @@ function onConnect() {
*/ */
MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false); MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false);
/*
* Init PIDs bank with a length that depends on the version
*/
let pidCount;
if (semver.gte(CONFIG.flightControllerVersion, "2.5.0")) {
pidCount = 11;
} else {
pidCount = 10;
}
for (let i = 0; i < pidCount; i++) {
PIDs.push(new Array(4));
}
helper.interval.add('msp-load-update', function () { helper.interval.add('msp-load-update', function () {
$('#msp-version').text("MSP version: " + MSP.protocolVersion.toFixed(0)); $('#msp-version').text("MSP version: " + MSP.protocolVersion.toFixed(0));
$('#msp-load').text("MSP load: " + helper.mspQueue.getLoad().toFixed(1)); $('#msp-load').text("MSP load: " + helper.mspQueue.getLoad().toFixed(1));

@ -1,7 +1,7 @@
/*global $*/ /*global $*/
'use strict'; 'use strict';
var ServoMixRule = function (target, input, rate, speed) { let ServoMixRule = function (target, input, rate, speed, condition) {
var self = {}; var self = {};
@ -41,5 +41,13 @@ var ServoMixRule = function (target, input, rate, speed) {
return rate !== 0; return rate !== 0;
}; };
self.getConditionId = function () {
return (condition == undefined) ? -1 : condition;
};
self.setConditionId = function (data) {
condition = data;
};
return self; return self;
}; };

@ -1,11 +1,11 @@
/*global ServoMixRule*/ /*global ServoMixRule*/
'use strict'; 'use strict';
var ServoMixerRuleCollection = function () { let ServoMixerRuleCollection = function () {
let self = {}, let self = {},
data = [], data = [],
maxServoCount = 8; maxServoCount = 16;
self.setServoCount = function (value) { self.setServoCount = function (value) {
maxServoCount = value; maxServoCount = value;
@ -70,6 +70,31 @@ var ServoMixerRuleCollection = function () {
} }
} }
return false; return false;
};
self.getNumberOfConfiguredServos = function () {
let count = 0;
for (let i = 0; i < self.getServoCount(); i ++) {
if (self.isServoConfigured(i)) {
count++;
}
}
return count;
};
self.getUsedServoIndexes = function () {
let out = [];
for (let ruleIndex in data) {
if (data.hasOwnProperty(ruleIndex)) {
let rule = data[ruleIndex];
out.push(rule.getTarget());
}
}
return jQuery.unique(out).sort(function(a, b){
return a-b;
});
} }
return self; return self;

@ -50,6 +50,20 @@ var Settings = (function () {
} }
} else if (s.setting.type == 'string') { } else if (s.setting.type == 'string') {
input.val(s.value); input.val(s.value);
} else if (s.setting.type == 'float') {
input.attr('type', 'number');
let dataStep = input.data("step");
if (dataStep !== undefined) {
input.attr('step', dataStep);
} else {
input.attr('step', "0.01");
}
input.attr('min', s.setting.min);
input.attr('max', s.setting.max);
input.val(s.value.toFixed(2));
} else { } else {
var multiplier = parseFloat(input.data('setting-multiplier') || 1); var multiplier = parseFloat(input.data('setting-multiplier') || 1);
input.attr('type', 'number'); input.attr('type', 'number');
@ -72,6 +86,11 @@ var Settings = (function () {
var settingName = input.data('setting'); var settingName = input.data('setting');
var setting = input.data('setting-info'); var setting = input.data('setting-info');
var value; var value;
if (typeof setting == 'undefined') {
return null;
}
if (setting.table) { if (setting.table) {
if (input.attr('type') == 'checkbox') { if (input.attr('type') == 'checkbox') {
value = input.prop('checked') ? 1 : 0; value = input.prop('checked') ? 1 : 0;

@ -0,0 +1,27 @@
'use strict';
var helper = helper || {};
helper.tabs = (function () {
let self = {},
$container;
function onHeaderClick(event) {
let $cT = $(event.currentTarget),
attrFor = $cT.attr("for");
$container.find('.subtab__header_label').removeClass("subtab__header_label--current");
$cT.addClass("subtab__header_label--current");
$container.find(".subtab__content--current").removeClass("subtab__content--current");
$container.find("#" + attrFor).addClass("subtab__content--current");
};
self.init = function ($dom) {
$container = $dom;
$container.find(".subtab__header_label").click(onHeaderClick);
};
return self;
})();

@ -15,9 +15,7 @@ helper.task = (function () {
publicScope.statusPullStart = function () { publicScope.statusPullStart = function () {
helper.interval.add('status_pull', function () { helper.interval.add('status_pull', function () {
MSP.send_message(MSPCodes.MSP_STATUS, false, false, function () { MSP.send_message(MSPCodes.MSP_STATUS, false, false, function () {
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) { MSP.send_message(MSPCodes.MSP_SENSOR_STATUS);
MSP.send_message(MSPCodes.MSP_SENSOR_STATUS);
}
}); });
}, privateScope.getStatusPullInterval(), true); }, privateScope.getStatusPullInterval(), true);

@ -24,10 +24,10 @@ var VTX = (function() {
} }
self.getMaxPower = function(vtxDev) { self.getMaxPower = function(vtxDev) {
if (vtxDev == self.DEV_SMARTAUDIO) { if ((vtxDev == self.DEV_SMARTAUDIO) || (vtxDev == self.DEV_TRAMP)) {
return 4; return 5;
} }
return 5; return 3;
} }
self.LOW_POWER_DISARM_MIN = 0; self.LOW_POWER_DISARM_MIN = 0;

@ -101,6 +101,14 @@ input[type="number"]::-webkit-inner-spin-button {
height: calc(100% - 7px); height: calc(100% - 7px);
} }
.mt1em {
margin-top: 1em !important;
}
.mb1em {
margin-bottom: 1em !important;
}
.margin-top { .margin-top {
margin-top: 20px; margin-top: 20px;
} }
@ -228,10 +236,6 @@ input[type="number"]::-webkit-inner-spin-button {
width: 136px; width: 136px;
} }
#port-picker .auto_connect {
color: #ddd;
}
#header_dataflash { #header_dataflash {
display: none; display: none;
} }
@ -981,6 +985,14 @@ li.active .ic_mixer {
/* Cause the height to shrink to contain its floated contents while log is open */ /* Cause the height to shrink to contain its floated contents while log is open */
} }
#content.loading {
overflow-y: hidden;
}
#content.loading > * {
opacity: 0;
}
#status-bar { #status-bar {
position: fixed; position: fixed;
bottom: 0; bottom: 0;
@ -1011,9 +1023,17 @@ li.active .ic_mixer {
} }
.data-loading { .data-loading {
z-index: 10000;
position: absolute;
top: 0;
width: 100%; width: 100%;
height: 100%; height: 100%;
background: url('../images/loading-bars.svg') no-repeat center 45%; background: url('../images/loading-bars.svg') no-repeat center 45%;
background-color: #FFF;
}
#content.loading .data-loading {
opacity: 1;
} }
.data-loading p { .data-loading p {
@ -1046,6 +1066,15 @@ dialog {
margin-bottom: 15px; margin-bottom: 15px;
} }
.tab_subtitle {
border-bottom: 1px solid #37a8db;
font-size: 1.5em;
line-height: 1.5em;
height: 25px;
font-family: 'open_sanslight', Arial, serif;
margin-bottom: 8px;
}
/* Note */ /* Note */
.note { .note {
background-color: #fff7cd; background-color: #fff7cd;
@ -1284,7 +1313,6 @@ dialog {
width: 100%; width: 100%;
height: 27px; height: 27px;
padding-bottom: 0; padding-bottom: 0;
float: left;
margin-bottom: 7px; margin-bottom: 7px;
font-family: 'open_sanssemibold', Arial, serif; font-family: 'open_sanssemibold', Arial, serif;
} }
@ -1446,15 +1474,16 @@ dialog {
transition: all ease 0.2s; transition: all ease 0.2s;
} }
.red a { .btn.red a,
/* background-color: #37a8db; */ .btn.red a:active {
background-color: #fafafa;
text-shadow: 0 1px rgba(0, 0, 0, 0.25); text-shadow: 0 1px rgba(0, 0, 0, 0.25);
color: #ff1e1e; color: #ff1e1e;
border: 1px solid #a00000; border: 1px solid #a00000;
transition: all ease 0.2s; transition: all ease 0.2s;
} }
.red a:hover { .btn.red a:hover {
background-color: #f86975; background-color: #f86975;
border: 1px solid #a00000; border: 1px solid #a00000;
text-shadow: 0 1px rgba(0, 0, 0, 0.25); text-shadow: 0 1px rgba(0, 0, 0, 0.25);
@ -2048,4 +2077,74 @@ select {
.text-center { .text-center {
text-align: center; text-align: center;
} }
.warning-box {
background-color: red;
color: white;
font-weight: bold;
margin: 0.4em 0;
padding: 1em;
clear: both;
}
.info-box {
background-color: darkgoldenrod;
color: white;
font-weight: bold;
margin: 0.4em 0;
padding: 1em;
clear: both;
}
.ok-box {
background-color: green;
color: white;
font-weight: bold;
margin: 0.4em 0;
padding: 1em;
clear: both;
}
#modal-reconnect {
/* width: 100%; */
height: 90px;
background: url(../images/loading-bars.svg) no-repeat center 100%;
}
#modal-reconnect div {
text-align: center;
}
.subtab__header {
padding: 0;
height: auto;
}
.subtab__header_label {
display: inline-block;
padding: 0 1em;
background-color: #eee;
min-width: 7em;
height: 1.5em;
line-height: 1.5em;
cursor: pointer;
font-size: 18px;
}
.subtab__header_label--current {
font-weight: bold;
background-color: #ccc;
}
.subtab__header_label:hover {
background-color: #c5c5c5;
}
.subtab__content {
display: none;
}
.subtab__content--current {
display: block;
}

@ -1,56 +1,57 @@
<!DOCTYPE html> <!DOCTYPE html>
<html> <html>
<head> <head>
<meta http-equiv="Content-Type" content="text/html; charset=utf-8"/> <meta http-equiv="Content-Type" content="text/html; charset=utf-8" />
<link type="text/css" rel="stylesheet" href="./build/styles.css" media="all"/> <link type="text/css" rel="stylesheet" href="./build/styles.css" media="all" />
<script type="text/javascript" src="./build/script.js"></script> <script type="text/javascript" src="./build/script.js"></script>
<title></title> <title></title>
</head> </head>
<body> <body>
<div id="main-wrapper"> <div id="main-wrapper">
<div id="appUpdateNotification" class="is-hidden"> <div id="appUpdateNotification" class="is-hidden">
<div class="modal__content"> <div class="modal__content">
<h1 class="modal__title modal__title" data-i18n="appUpdateNotificationHeader"></h1> <h1 class="modal__title modal__title" data-i18n="appUpdateNotificationHeader"></h1>
<div class="modal__text" data-i18n="appUpdateNotificationDescription"></div> <div class="modal__text" data-i18n="appUpdateNotificationDescription"></div>
</div> </div>
<div class="modal__buttons modal__buttons--upbottom"> <div class="modal__buttons modal__buttons--upbottom">
<a href="https://github.com/iNavFlight/inav-configurator/releases" target="_blank" id="update-notification-download" <a href="https://github.com/iNavFlight/inav-configurator/releases" target="_blank" id="update-notification-download" class="modal__button modal__button--main modal__button--main--inline" data-i18n="downloadUpdatesBtn"></a>
class="modal__button modal__button--main modal__button--main--inline" data-i18n="downloadUpdatesBtn"></a> <a id="update-notification-close" class="modal__button modal__button--main modal__button--main--inline" data-i18n="closeUpdateBtn"></a>
<a id="update-notification-close" class="modal__button modal__button--main modal__button--main--inline" data-i18n="closeUpdateBtn"></a>
</div>
</div>
<div class="headerbar">
<div id="logo">
<div class="logo_text">
CONFIGURATOR
<div class="version"></div>
</div> </div>
</div> </div>
<a id="options" href="#" data-i18n_title="options_title"></a> <div class="headerbar">
<div id="logo">
<div id="port-picker"> <div class="logo_text">
<div class="connect_controls" id="connectbutton"> CONFIGURATOR
<div class="connect_b"> <div class="version"></div>
<a class="connect" href="#"></a>
</div> </div>
<a class="connect_state" data-i18n="connect"></a>
</div> </div>
<div id="portsinput"> <a id="options" href="#" data-i18n_title="options_title"></a>
<div class="portsinput__row">
<div id="port-override-option" class="portsinput__top-element portsinput__top-element--port-override"> <div id="port-picker">
<label for="port-override">Port: </label> <div class="connect_controls" id="connectbutton">
<input id="port-override" type="text" value="/dev/rfcomm0"/> <div class="connect_b">
<a class="connect" href="#"></a>
</div> </div>
<div class="dropdown dropdown-dark portsinput__top-element"> <a class="connect_state" data-i18n="connect"></a>
<!--suppress HtmlFormInputWithoutLabel --> </div>
<select class="dropdown-select" id="port" title="Port"> <div id="portsinput">
<div class="portsinput__row">
<div id="port-override-option" class="portsinput__top-element portsinput__top-element--port-override">
<label for="port-override">Port: </label>
<input id="port-override" type="text" value="/dev/rfcomm0" />
</div>
<div class="dropdown dropdown-dark portsinput__top-element">
<!--suppress HtmlFormInputWithoutLabel -->
<select class="dropdown-select" id="port" title="Port">
<option value="manual">Manual</option> <option value="manual">Manual</option>
<!-- port list gets generated here --> <!-- port list gets generated here -->
</select> </select>
</div> </div>
<div class="dropdown dropdown-dark portsinput__top-element"> <div class="dropdown dropdown-dark portsinput__top-element">
<!--suppress HtmlFormInputWithoutLabel --> <!--suppress HtmlFormInputWithoutLabel -->
<select class="dropdown-select" id="baud" title="Baud Rate"> <select class="dropdown-select" id="baud" title="Baud Rate">
<option value="115200" selected="selected">115200</option> <option value="115200" selected="selected">115200</option>
<option value="57600">57600</option> <option value="57600">57600</option>
<option value="38400">38400</option> <option value="38400">38400</option>
@ -62,202 +63,243 @@
<option value="2400">2400</option> <option value="2400">2400</option>
<option value="1200">1200</option> <option value="1200">1200</option>
</select> </select>
</div>
</div> </div>
</div> <div class="portsinput__row">
<div class="portsinput__row"> <div class="portsinput__top-element portsinput__top-element--inline">
<div class="portsinput__top-element portsinput__top-element--inline"> <label for="wireless-mode">
<label for="wireless-mode">
<span class="" data-i18n="wirelessModeSwitch"></span> <span class="" data-i18n="wirelessModeSwitch"></span>
</label> </label>
<input id="wireless-mode" class=" togglesmall" type="checkbox"/> <input id="wireless-mode" class=" togglesmall" type="checkbox" />
</div> </div>
<div class="portsinput__top-element portsinput__top-element--inline">
<label for="auto-connect">
<span class="auto_connect" data-i18n="autoConnect"></span>
</label>
<input id="auto-connect" class="auto_connect togglesmall" type="checkbox"/>
</div> </div>
</div> </div>
</div> </div>
</div> <div class="header-wrapper">
<div class="header-wrapper"> <div id="dataflash_wrapper_global">
<div id="dataflash_wrapper_global"> <div class="noflash_global" align="center">No dataflash <br>chip found</div>
<div class="noflash_global" align="center">No dataflash <br>chip found</div> <ul class="dataflash-contents_global">
<ul class="dataflash-contents_global"> <li class="dataflash-free_global">
<li class="dataflash-free_global"> <div class="legend">Dataflash: free space</div>
<div class="legend">Dataflash: free space</div> </li>
</li> </ul>
</ul> <div id="profile_change">
<div id="profile_change"> <div class="dropdown dropdown-dark">
<div class="dropdown dropdown-dark"> <form name="profile-change" id="profile-change">
<form name="profile-change" id="profile-change"> <!--suppress HtmlFormInputWithoutLabel -->
<!--suppress HtmlFormInputWithoutLabel --> <select class="dropdown-select" id="profilechange">
<select class="dropdown-select" id="profilechange">
<option value="0">Profile 1</option> <option value="0">Profile 1</option>
<option value="1">Profile 2</option> <option value="1">Profile 2</option>
<option value="2">Profile 3</option> <option value="2">Profile 3</option>
</select> </select>
</form> </form>
</div>
</div> </div>
</div> <div id="battery_profile_change">
<div id="battery_profile_change"> <div class="dropdown dropdown-dark">
<div class="dropdown dropdown-dark"> <form name="battery-profile-change" id="battery-profile-change">
<form name="battery-profile-change" id="battery-profile-change"> <!--suppress HtmlFormInputWithoutLabel -->
<!--suppress HtmlFormInputWithoutLabel --> <select class="dropdown-select" id="batteryprofilechange">
<select class="dropdown-select" id="batteryprofilechange">
<option value="0">Battery profile 1</option> <option value="0">Battery profile 1</option>
<option value="1">Battery profile 2</option> <option value="1">Battery profile 2</option>
<option value="2">Battery profile 3</option> <option value="2">Battery profile 3</option>
</select> </select>
</form> </form>
</div>
</div>
</div>
<div id="sensor-status" class="sensor_state mode-connected">
<ul>
<li class="gyro" title="Gyroscope">
<div class="gyroicon">Gyro</div>
</li>
<li class="accel" title="Accelerometer">
<div class="accicon">Accel</div>
</li>
<li class="mag" title="Magnetometer">
<div class="magicon">Mag</div>
</li>
<li class="baro" title="Barometer">
<div class="baroicon">Baro</div>
</li>
<li class="gps" title="GPS">
<div class="gpsicon">GPS</div>
</li>
<li class="opflow" title="Optical flow">
<div class="opflowicon">Flow</div>
</li>
<li class="sonar" title="Sonar / Range finder">
<div class="sonaricon">Sonar</div>
</li>
<li class="airspeed" title="Airspeed">
<div class="airspeedicon">Speed</div>
</li>
</ul>
</div>
<div id="quad-status_wrapper">
<div class="battery-icon">
<div class="quad-status-contents">
<div class="battery-status"></div>
</div>
</div>
<div class="battery-legend">Battery voltage</div>
<div class="bottomStatusIcons">
<div class="armedicon cf_tip" data-i18n_title="mainHelpArmed"></div>
<div class="failsafeicon cf_tip" data-i18n_title="mainHelpFailsafe"></div>
<div class="linkicon cf_tip" data-i18n_title="mainHelpLink"></div>
</div> </div>
</div> </div>
</div> </div>
<div id="sensor-status" class="sensor_state mode-connected"> </div>
<ul> <div class="clear-both"></div>
<li class="gyro" title="Gyroscope"> <div id="log">
<div class="gyroicon">Gyro</div> <div class="logswitch">
<a href="#" id="showlog">Show Log</a>
</div>
<div id="scrollicon"></div>
<div class="wrapper"></div>
</div>
<div class="tab_container">
<div id="tabs">
<ul class="mode-disconnected">
<li class="tab_landing">
<a href="#" data-i18n="tabLanding" class="tabicon ic_welcome" title="Welcome"></a>
</li>
<li class="tab_help">
<a href="https://github.com/iNavFlight/inav/wiki" target="_blank" data-i18n="tabHelp" class="tabicon ic_help" title="Documentation &amp; Support"></a>
</li>
<li class="tab_mission_control">
<a href="#" data-i18n="tabMissionControl" class="tabicon ic_mission" title="Mission Control"></a>
</li>
<li class="tab_firmware_flasher">
<a href="#" data-i18n="tabFirmwareFlasher" class="tabicon ic_flasher" title="Firmware Flasher"></a>
</li>
</ul>
<ul class="mode-connected">
<li class="tab_setup">
<a href="#" data-i18n="tabSetup" class="tabicon ic_setup" title="Setup"></a>
</li>
<li class="tab_calibration">
<a href="#" data-i18n="tabCalibration" class="tabicon ic_calibration" title="Calibration"></a>
</li>
<li class="tab_mixer">
<a href="#" data-i18n="tabMixer" class="tabicon ic_mixer" title="Mixer"></a>
</li>
<li class="tab_outputs">
<a href="#" data-i18n="tabOutputs" class="tabicon ic_motor" title="Outputs"></a>
</li>
<li class="tab_profiles">
<a href="#" data-i18n="tabPresets" class="tabicon ic_wizzard" title="Presets"></a>
</li>
<li class="tab_ports">
<a href="#" data-i18n="tabPorts" class="tabicon ic_ports" title="Ports"></a>
</li>
<li class="tab_configuration">
<a href="#" data-i18n="tabConfiguration" class="tabicon ic_config" title="Configuration"></a>
</li> </li>
<li class="accel" title="Accelerometer"> <li class="tab_failsafe">
<div class="accicon">Accel</div> <a href="#" data-i18n="tabFailsafe" class="tabicon ic_failsafe" title="Failsafe"></a>
</li> </li>
<li class="mag" title="Magnetometer"> <li class="tab_pid_tuning">
<div class="magicon">Mag</div> <a href="#" data-i18n="tabPidTuning" class="tabicon ic_pid" title="PID Tuning"></a>
</li> </li>
<li class="baro" title="Barometer"> <li class="tab_advanced_tuning">
<div class="baroicon">Baro</div> <a href="#" data-i18n="tabAdvancedTuning" class="tabicon ic_advanced" title="Advanced Tuning"></a>
</li> </li>
<li class="gps" title="GPS">
<div class="gpsicon">GPS</div> <li class="tab_receiver">
<a href="#" data-i18n="tabReceiver" class="tabicon ic_rx" title="Receiver"></a>
</li>
<li class="tab_auxiliary">
<a href="#" data-i18n="tabAuxiliary" class="tabicon ic_modes" title="Modes"></a>
</li>
<li class="tab_adjustments">
<a href="#" data-i18n="tabAdjustments" class="tabicon ic_adjust" title="Adjustments"></a>
</li>
<li class="tab_gps">
<a href="#" data-i18n="tabGPS" class="tabicon ic_gps" title="GPS"></a>
</li>
<li class="tab_mission_control">
<a href="#" data-i18n="tabMissionControl" class="tabicon ic_mission" title="Mission Control"></a>
</li>
<li class="tab_osd">
<a href="#" data-i18n="tabOSD" class="tabicon ic_osd" title="OSD"></a>
</li> </li>
<li class="opflow" title="Optical flow"> <!--<li class="tab_transponder"><a href="#" data-i18n="tabTransponder" class="tabicon ic_transponder" title="Transponder"></a></li>-->
<div class="opflowicon">Flow</div> <li class="tab_led_strip">
<a href="#" data-i18n="tabLedStrip" class="tabicon ic_led" title="LED Strip"></a>
</li> </li>
<li class="sonar" title="Sonar / Range finder"> <li class="tab_sensors">
<div class="sonaricon">Sonar</div> <a href="#" data-i18n="tabRawSensorData" class="tabicon ic_sensors" title="Sensors"></a>
</li> </li>
<li class="airspeed" title="Airspeed"> <li class="tab_logging">
<div class="airspeedicon">Speed</div> <a href="#" data-i18n="tabLogging" class="tabicon ic_log" title="Tethered Logging"></a>
</li> </li>
<li class="tab_onboard_logging">
<a href="#" data-i18n="tabOnboardLogging" class="tabicon ic_data" title="Onboard Logging"></a>
</li>
<li class="tab_cli">
<a href="#" data-i18n="tabCLI" class="tabicon ic_cli" title="CLI"></a>
</li>
<!--<li class=""><a href="#" class="tabicon ic_advanced">Advanced (spare icon)</a></li>-->
<!--<li class=""><a href="#" class="tabicon ic_wizzard">Wizzard (spare icon)</a></li>-->
</ul> </ul>
</div> </div>
<div id="quad-status_wrapper"> <div class="clear-both"></div>
<div class="battery-icon">
<div class="quad-status-contents">
<div class="battery-status"></div>
</div>
</div>
<div class="battery-legend">Battery voltage</div>
<div class="bottomStatusIcons">
<div class="armedicon cf_tip" data-i18n_title="mainHelpArmed"></div>
<div class="failsafeicon cf_tip" data-i18n_title="mainHelpFailsafe"></div>
<div class="linkicon cf_tip" data-i18n_title="mainHelpLink"></div>
</div>
</div>
</div> </div>
</div> <div id="content"></div>
<div class="clear-both"></div> <div id="status-bar">
<div id="log"> <div>
<div class="logswitch"> <span data-i18n="statusbar_packet_error"></span> <span class="packet-error">0</span>
<a href="#" id="showlog">Show Log</a> </div>
<div>
<span data-i18n="statusbar_i2c_error"></span> <span class="i2c-error">0</span>
</div>
<div>
<span data-i18n="statusbar_cycle_time"></span> <span class="cycle-time">0</span>
</div>
<div>
<span class="cpu-load"> </span>
</div>
<div>
<span id="msp-version"> </span>
</div>
<div>
<span id="msp-load"> </span>
</div>
<div>
<span id="msp-roundtrip"> </span>
</div>
<div>
<span id="hardware-roundtrip"> </span>
</div>
<div>
<span id="drop-rate"> </span>
</div>
<div class="version">
<!-- configuration version generated here -->
</div>
</div> </div>
<div id="scrollicon"></div> <div id="cache">
<div class="wrapper"></div> <div class="data-loading">
</div> <p>Waiting for data ...</p>
<div class="tab_container"> </div>
<div id="tabs">
<ul class="mode-disconnected">
<li class="tab_landing"><a href="#" data-i18n="tabLanding" class="tabicon ic_welcome"
title="Welcome"></a></li>
<li class="tab_help"><a href="#" data-i18n="tabHelp" class="tabicon ic_help"
title="Documentation &amp; Support"></a></li>
<li class="tab_firmware_flasher"><a href="#" data-i18n="tabFirmwareFlasher" class="tabicon ic_flasher"
title="Firmware Flasher"></a></li>
</ul>
<ul class="mode-connected">
<li class="tab_setup"><a href="#" data-i18n="tabSetup" class="tabicon ic_setup" title="Setup"></a></li>
<li class="tab_calibration"><a href="#" data-i18n="tabCalibration" class="tabicon ic_calibration" title="Calibration"></a></li>
<li class="tab_mixer"><a href="#" data-i18n="tabMixer" class="tabicon ic_mixer" title="Mixer"></a></li>
<li class="tab_profiles"><a href="#" data-i18n="tabPresets" class="tabicon ic_wizzard"
title="Presets"></a></li>
<li class="tab_ports"><a href="#" data-i18n="tabPorts" class="tabicon ic_ports" title="Ports"></a></li>
<li class="tab_configuration"><a href="#" data-i18n="tabConfiguration" class="tabicon ic_config"
title="Configuration"></a></li>
<li class="tab_failsafe"><a href="#" data-i18n="tabFailsafe" class="tabicon ic_failsafe"
title="Failsafe"></a></li>
<li class="tab_pid_tuning"><a href="#" data-i18n="tabPidTuning" class="tabicon ic_pid"
title="PID Tuning"></a></li>
<li class="tab_advanced_tuning"><a href="#" data-i18n="tabAdvancedTuning" class="tabicon ic_advanced" title="Advanced Tuning"></a></li>
<li class="tab_receiver"><a href="#" data-i18n="tabReceiver" class="tabicon ic_rx" title="Receiver"></a>
</li>
<li class="tab_auxiliary"><a href="#" data-i18n="tabAuxiliary" class="tabicon ic_modes"
title="Modes"></a></li>
<li class="tab_adjustments"><a href="#" data-i18n="tabAdjustments" class="tabicon ic_adjust"
title="Adjustments"></a></li>
<li class="tab_servos"><a href="#" data-i18n="tabServos" class="tabicon ic_servo" title="Servos"></a>
</li>
<li class="tab_gps"><a href="#" data-i18n="tabGPS" class="tabicon ic_gps" title="GPS"></a></li>
<li class="tab_mission_control"><a href="#" data-i18n="tabMissionControl" class="tabicon ic_mission" title="Mission Control"></a></li>
<li class="tab_motors"><a href="#" data-i18n="tabMotorTesting" class="tabicon ic_motor"
title="Motors"></a></li>
<li class="tab_osd"><a href="#" data-i18n="tabOSD" class="tabicon ic_osd" title="OSD"></a></li>
<!--<li class="tab_transponder"><a href="#" data-i18n="tabTransponder" class="tabicon ic_transponder" title="Transponder"></a></li>-->
<li class="tab_led_strip"><a href="#" data-i18n="tabLedStrip" class="tabicon ic_led"
title="LED Strip"></a></li>
<li class="tab_sensors"><a href="#" data-i18n="tabRawSensorData" class="tabicon ic_sensors"
title="Sensors"></a></li>
<li class="tab_logging"><a href="#" data-i18n="tabLogging" class="tabicon ic_log"
title="Tethered Logging"></a></li>
<li class="tab_onboard_logging"><a href="#" data-i18n="tabOnboardLogging" class="tabicon ic_data"
title="Onboard Logging"></a></li>
<li class="tab_cli"><a href="#" data-i18n="tabCLI" class="tabicon ic_cli" title="CLI"></a></li>
<!--<li class=""><a href="#" class="tabicon ic_advanced">Advanced (spare icon)</a></li>-->
<!--<li class=""><a href="#" class="tabicon ic_wizzard">Wizzard (spare icon)</a></li>-->
</ul>
</div> </div>
<div class="clear-both"></div>
</div> </div>
<div id="content"></div> <div id="modal-reconnect" class="is-hidden">
<div id="status-bar"> <div data-i18n="deviceRebooting"></div>
<div>
<span data-i18n="statusbar_packet_error"></span> <span class="packet-error">0</span>
</div>
<div>
<span data-i18n="statusbar_i2c_error"></span> <span class="i2c-error">0</span>
</div>
<div>
<span data-i18n="statusbar_cycle_time"></span> <span class="cycle-time">0</span>
</div>
<div>
<span class="cpu-load"> </span>
</div>
<div>
<span id="msp-version"> </span>
</div>
<div>
<span id="msp-load"> </span>
</div>
<div>
<span id="msp-roundtrip"> </span>
</div>
<div>
<span id="hardware-roundtrip"> </span>
</div>
<div>
<span id="drop-rate"> </span>
</div>
<div class="version">
<!-- configuration version generated here -->
</div>
</div> </div>
<div id="cache"> <div id="defaults-wrapper" style="display: none">
<div class="data-loading"> <div class="defaults-dialog__background"></div>
<p>Waiting for data ...</p> <div class="defaults-dialog__content">
<div class="tab_title" data-i18n="defaultsDialogTitle"></div>
<div class="defaults-dialog__content--wrapper">
<p class="defaults-dialog__info" data-i18n="defaultsDialogInfo"></p>
<div class="defaults-dialog__options"></div>
</div>
</div> </div>
</div> </div>
</div>
</body> </body>
</html> </html>

@ -91,20 +91,10 @@ $(document).ready(function () {
} }
}); });
win.setMinimumSize(1024, 800); win.setMinimumSize(800, 600);
win.on('close', function () { win.on('close', function () {
//Save window size and position //Save window size and position
// var height = win.height;
// var width = win.width;
//
// if (height < 400) {
// height = 400
// }
// if (width < 512) {
// width = 512
// }
chrome.storage.local.set({'windowSize': {height: win.height, width: win.width, x: win.x, y: win.y}}, function () { chrome.storage.local.set({'windowSize': {height: win.height, width: win.width, x: win.x, y: win.y}}, function () {
// Notify that we saved. // Notify that we saved.
console.log('Settings saved'); console.log('Settings saved');
@ -123,7 +113,6 @@ $(document).ready(function () {
} }
}); });
//set '1.8.0' for test
appUpdater.checkRelease(chrome.runtime.getManifest().version); appUpdater.checkRelease(chrome.runtime.getManifest().version);
// log library versions in console to make version tracking easier // log library versions in console to make version tracking easier
@ -132,6 +121,11 @@ $(document).ready(function () {
// Tabs // Tabs
var ui_tabs = $('#tabs > ul'); var ui_tabs = $('#tabs > ul');
$('a', ui_tabs).click(function () { $('a', ui_tabs).click(function () {
if ($(this).parent().hasClass("tab_help")) {
return;
}
if ($(this).parent().hasClass('active') == false && !GUI.tab_switch_in_progress) { // only initialize when the tab isn't already active if ($(this).parent().hasClass('active') == false && !GUI.tab_switch_in_progress) { // only initialize when the tab isn't already active
var self = this, var self = this,
tabClass = $(self).parent().prop('class'); tabClass = $(self).parent().prop('class');
@ -141,12 +135,6 @@ $(document).ready(function () {
var tab = tabClass.substring(4); var tab = tabClass.substring(4);
var tabName = $(self).text(); var tabName = $(self).text();
if (CONFIGURATOR.connectionValid && semver.lt(CONFIG.flightControllerVersion, "2.0.0")) {
$('#battery_profile_change').hide();
$('#profile_change').css('width', '125px');
$('#dataflash_wrapper_global').css('width', '125px');
}
if (tabRequiresConnection && !CONFIGURATOR.connectionValid) { if (tabRequiresConnection && !CONFIGURATOR.connectionValid) {
GUI.log(chrome.i18n.getMessage('tabSwitchConnectionRequired')); GUI.log(chrome.i18n.getMessage('tabSwitchConnectionRequired'));
return; return;
@ -173,6 +161,7 @@ $(document).ready(function () {
// detach listeners and remove element data // detach listeners and remove element data
var content = $('#content'); var content = $('#content');
content.data('empty', !!content.is(':empty'));
content.empty(); content.empty();
// display loading screen // display loading screen
@ -189,10 +178,6 @@ $(document).ready(function () {
case 'firmware_flasher': case 'firmware_flasher':
TABS.firmware_flasher.initialize(content_ready); TABS.firmware_flasher.initialize(content_ready);
break; break;
case 'help':
TABS.help.initialize(content_ready);
break;
case 'auxiliary': case 'auxiliary':
TABS.auxiliary.initialize(content_ready); TABS.auxiliary.initialize(content_ready);
break; break;
@ -244,8 +229,8 @@ $(document).ready(function () {
case 'mixer': case 'mixer':
TABS.mixer.initialize(content_ready); TABS.mixer.initialize(content_ready);
break; break;
case 'motors': case 'outputs':
TABS.motors.initialize(content_ready); TABS.outputs.initialize(content_ready);
break; break;
case 'osd': case 'osd':
TABS.osd.initialize(content_ready); TABS.osd.initialize(content_ready);

@ -1,7 +1,7 @@
{ {
"manifest_version": 2, "manifest_version": 2,
"minimum_chrome_version": "38", "minimum_chrome_version": "38",
"version": "2.1.0", "version": "2.5.0",
"author": "Several", "author": "Several",
"name": "INAV - Configurator", "name": "INAV - Configurator",
"short_name": "INAV", "short_name": "INAV",

2418
package-lock.json generated

File diff suppressed because it is too large Load Diff

@ -1,11 +1,13 @@
{ {
"name": "inav-configurator", "name": "inav-configurator",
"description": "INAV Configurator", "description": "INAV Configurator",
"version": "2.1.0", "version": "2.5.0",
"main": "main.html", "main": "main.html",
"default_locale": "en", "default_locale": "en",
"scripts": { "scripts": {
"start": "node_modules/gulp/bin/gulp.js build && node_modules/nw/bin/nw ." "start": "node node_modules/gulp/bin/gulp.js build && node node_modules/nw/bin/nw .",
"gulp": "gulp",
"nw": "nw"
}, },
"window": { "window": {
"title": "INAV Configurator", "title": "INAV Configurator",
@ -24,18 +26,24 @@
"archiver": "^2.0.3", "archiver": "^2.0.3",
"bluebird": "3.4.1", "bluebird": "3.4.1",
"del": "^3.0.0", "del": "^3.0.0",
"graceful-fs": "^4.1.11", "fs": "0.0.1-security",
"gulp": "^4.0.0", "graceful-fs": "^4.2.0",
"gulp": "^4.0.2",
"gulp-concat": "^2.6.1", "gulp-concat": "^2.6.1",
"inflection": "1.12.0", "inflection": "1.12.0",
"jquery": "2.1.4", "jquery": "2.1.4",
"jquery-ui-npm": "1.12.0", "jquery-ui-npm": "1.12.0",
"marked": "^0.3.17", "marked": "^0.3.17",
"minimist": "^1.2.0", "minimist": "^1.2.0",
"nw": "^0.31.4-sdk", "nw": "^0.42.2-sdk",
"nw-builder": "^3.5.4", "nw-dialog": "^1.0.7",
"openlayers": "^4.6.5", "openlayers": "^4.6.5",
"temp": "^0.8.3", "temp": "^0.8.3",
"three": "0.72.0" "three": "0.72.0",
"xml2js": "^0.4.19"
},
"devDependencies": {
"nw-builder": "^3.5.7",
"semver": "6.3.0"
} }
} }

@ -4,7 +4,7 @@
FONT_VERSION = 1 FONT_VERSION = 1
FONTS = default vision vision-alt clarity clarity_medium bold large FONTS = default vision impact impact_mini clarity clarity_medium bold large
CHARMAPS = $(addsuffix .mcm, $(FONTS)) CHARMAPS = $(addsuffix .mcm, $(FONTS))
PREVIEWS = $(addsuffix .png, $(FONTS)) PREVIEWS = $(addsuffix .png, $(FONTS))

File diff suppressed because it is too large Load Diff

Binary file not shown.

Before

Width:  |  Height:  |  Size: 248 B

After

Width:  |  Height:  |  Size: 229 B

Binary file not shown.

Before

Width:  |  Height:  |  Size: 123 B

After

Width:  |  Height:  |  Size: 198 B

Binary file not shown.

Before

Width:  |  Height:  |  Size: 136 B

After

Width:  |  Height:  |  Size: 205 B

Binary file not shown.

Before

Width:  |  Height:  |  Size: 127 B

After

Width:  |  Height:  |  Size: 200 B

Binary file not shown.

Before

Width:  |  Height:  |  Size: 121 B

After

Width:  |  Height:  |  Size: 195 B

Binary file not shown.

Before

Width:  |  Height:  |  Size: 133 B

After

Width:  |  Height:  |  Size: 205 B

Binary file not shown.

Before

Width:  |  Height:  |  Size: 131 B

After

Width:  |  Height:  |  Size: 201 B

Binary file not shown.

Before

Width:  |  Height:  |  Size: 126 B

After

Width:  |  Height:  |  Size: 198 B

Binary file not shown.

Before

Width:  |  Height:  |  Size: 132 B

After

Width:  |  Height:  |  Size: 204 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 201 B

Binary file not shown.

Before

Width:  |  Height:  |  Size: 102 B

After

Width:  |  Height:  |  Size: 240 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 204 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 219 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 208 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 237 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 236 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 236 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 253 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 247 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 214 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 259 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 253 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 253 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 261 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 258 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 225 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 184 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 201 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 208 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 215 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 248 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 260 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 277 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 272 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 271 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 248 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 194 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 206 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 209 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 192 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 213 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 210 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 192 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 215 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 216 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 202 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 221 B

Binary file not shown.

After

Width:  |  Height:  |  Size: 222 B

File diff suppressed because it is too large Load Diff

Binary file not shown.

Before

Width:  |  Height:  |  Size: 177 B

After

Width:  |  Height:  |  Size: 2.8 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 123 B

After

Width:  |  Height:  |  Size: 198 B

Binary file not shown.

Before

Width:  |  Height:  |  Size: 136 B

After

Width:  |  Height:  |  Size: 205 B

Binary file not shown.

Before

Width:  |  Height:  |  Size: 127 B

After

Width:  |  Height:  |  Size: 200 B

Binary file not shown.

Before

Width:  |  Height:  |  Size: 121 B

After

Width:  |  Height:  |  Size: 195 B

Binary file not shown.

Before

Width:  |  Height:  |  Size: 133 B

After

Width:  |  Height:  |  Size: 205 B

Binary file not shown.

Before

Width:  |  Height:  |  Size: 131 B

After

Width:  |  Height:  |  Size: 201 B

Some files were not shown because too many files have changed in this diff Show More

Loading…
Cancel
Save