mirror of
https://github.com/iNavFlight/inav-configurator.git
synced 2025-07-16 04:45:18 +03:00
Convert to CommonJS Modules - Part 2
This commit is contained in:
parent
91f1699659
commit
38727c54a8
21 changed files with 729 additions and 694 deletions
12
.vscode/launch.json
vendored
12
.vscode/launch.json
vendored
|
@ -16,18 +16,6 @@
|
|||
},
|
||||
"cwd": "${workspaceFolder}",
|
||||
"console": "integratedTerminal"
|
||||
},
|
||||
{
|
||||
"name": "Debug Main Process",
|
||||
"type": "node",
|
||||
"request": "launch",
|
||||
"cwd": "${workspaceFolder}",
|
||||
"runtimeExecutable": "${workspaceFolder}/node_modules/.bin/electron",
|
||||
"windows": {
|
||||
"runtimeExecutable": "${workspaceFolder}/node_modules/.bin/electron.cmd"
|
||||
},
|
||||
"args" : [".", "--trace-warnings"],
|
||||
"outputCapture": "std"
|
||||
}
|
||||
]
|
||||
}
|
21
README.md
21
README.md
|
@ -18,14 +18,6 @@ everything, the hardware is not working, or you have any other _support_ problem
|
|||
* [RC Groups Support](https://www.rcgroups.com/forums/showthread.php?2495732-Cleanflight-iNav-(navigation-rewrite)-project)
|
||||
* [INAV Official on Telegram](https://t.me/INAVFlight)
|
||||
|
||||
## INAV Configurator starts minimized, what should I do?
|
||||
|
||||
You have to remove the `C:\Users%Your_UserName%\AppData\Local\inav-configurator` folder and all its content.
|
||||
|
||||
[https://www.youtube.com/watch?v=XMoULyiFDp4](https://www.youtube.com/watch?v=XMoULyiFDp4)
|
||||
|
||||
Alternatively, on Windows with PowerShell, you can use the `post_install_cleanup.ps1` script that will do the cleaning. (thank you, James Cherrill)
|
||||
|
||||
## Installation
|
||||
|
||||
Depending on the target operating system, _INAV Configurator_ is distributed as a _standalone_ application or Chrome App.
|
||||
|
@ -78,17 +70,6 @@ sudo mv inav-configurator.desktop /usr/share/applications/
|
|||
* (5.0.0+) chrome_crashpad_handler `chmod +x /opt/inav/inav-configurator/chrome_crashpad_handler`
|
||||
11. Run the INAV Configurator app from the unpacked folder `/opt/inav/inav-configurator/inav-configurator`
|
||||
|
||||
#### Notes
|
||||
|
||||
On some Linux distros, you may be missing `libatomic` and/or `NW.JS` (especially `libnode.so`) dependencies. If so, please install `libatomic` using your distro's package manager, e.g:
|
||||
|
||||
* Arch Linux: `sudo pacman -S --needed libatomic_ops`
|
||||
* Debian / Ubuntu: `sudo apt install libatomic1`
|
||||
* Fedora: `sudo dnf install libatomic`
|
||||
|
||||
1. Don't forget to add your user to the dialout group "sudo usermod -aG dialout YOUR_USERNAME" for serial access
|
||||
2. If you have 3D model animation problems, enable "Override software rendering list" in Chrome flags chrome://flags/#ignore-gpu-blacklist
|
||||
|
||||
### Mac
|
||||
|
||||
1. Visit [release page](https://github.com/iNavFlight/inav-configurator/releases)
|
||||
|
@ -121,7 +102,7 @@ To be able to open Inspector, set envorinment variable `NODE_ENV` to `develpomen
|
|||
|
||||
``` NODE_ENV=development npm start ```
|
||||
|
||||
Or use vscode and start a debug session `Electron Main` (Just hit F5!)
|
||||
Or use vscode and start a debug session `Debug Configurator` (Just hit F5!)
|
||||
|
||||
## Different map providers
|
||||
|
||||
|
|
|
@ -218,19 +218,19 @@ $(function() {
|
|||
TABS.modes.initialize(content_ready);
|
||||
break;
|
||||
case 'gps':
|
||||
require('./../tabs');
|
||||
require('./../tabs/gps.js');
|
||||
TABS.gps.initialize(content_ready);
|
||||
break;
|
||||
case 'magnetometer':
|
||||
require('./../tabs');
|
||||
require('./../tabs/magnetometer.js');
|
||||
TABS.magnetometer.initialize(content_ready);
|
||||
break;
|
||||
case 'mission_control':
|
||||
require('./../tabs');
|
||||
require('./../tabs/mission_control.js');
|
||||
TABS.mission_control.initialize(content_ready);
|
||||
break;
|
||||
case 'mixer':
|
||||
require('./../tabs');
|
||||
require('./../tabs/mixer.js');
|
||||
TABS.mixer.initialize(content_ready);
|
||||
break;
|
||||
case 'outputs':
|
||||
|
|
7
js/fc.js
7
js/fc.js
|
@ -10,6 +10,7 @@ const ProgrammingPidStatus = require('./programmingPidStatus');
|
|||
const WaypointCollection = require('./waypointCollection');
|
||||
const OutputMappingCollection = require('./outputMapping');
|
||||
const SafehomeCollection = require('./safehomeCollection');
|
||||
const { PLATFORM } = require('./model.js')
|
||||
const VTX = require('./vtx');
|
||||
const BitHelper = require('./bitHelper');
|
||||
|
||||
|
@ -813,14 +814,14 @@ var FC = {
|
|||
var calibrated = true;
|
||||
var flagNames = FC.getArmingFlags();
|
||||
|
||||
if (CALIBRATION_DATA.accGain.X === 4096 && CALIBRATION_DATA.accGain.Y === 4096 && CALIBRATION_DATA.accGain.Z === 4096 &&
|
||||
CALIBRATION_DATA.accZero.X === 0 && CALIBRATION_DATA.accZero.Y === 0 && CALIBRATION_DATA.accZero.Z === 0
|
||||
if (this.CALIBRATION_DATA.accGain.X === 4096 && this.CALIBRATION_DATA.accGain.Y === 4096 && this.CALIBRATION_DATA.accGain.Z === 4096 &&
|
||||
this.CALIBRATION_DATA.accZero.X === 0 && this.CALIBRATION_DATA.accZero.Y === 0 && this.CALIBRATION_DATA.accZero.Z === 0
|
||||
) {
|
||||
calibrated = false;
|
||||
}
|
||||
|
||||
if ((calibrated) && flagNames.hasOwnProperty(13)) {
|
||||
if (BitHelper.bit_check(CONFIG.armingFlags, 13)) {
|
||||
if (BitHelper.bit_check(this.CONFIG.armingFlags, 13)) {
|
||||
calibrated = false;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -21,6 +21,11 @@ helper.features.execute(function () {
|
|||
});
|
||||
|
||||
*/
|
||||
|
||||
const mspHelper = require('./msp/MSPHelper');
|
||||
const BitHelper = require('./bitHelper');
|
||||
const FC = require('./fc');
|
||||
|
||||
var features = (function() {
|
||||
|
||||
let publicScope = {},
|
||||
|
@ -46,7 +51,7 @@ var features = (function() {
|
|||
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")));
|
||||
$this.prop('checked', BitHelper.bit_check(values, $this.attr("data-bit")));
|
||||
});
|
||||
};
|
||||
|
||||
|
@ -71,11 +76,11 @@ var features = (function() {
|
|||
privateScope.setBits = function () {
|
||||
|
||||
for (const bit of toSet) {
|
||||
FEATURES = bit_set(FEATURES, bit);
|
||||
FC.FEATURES = BitHelper.bit_set(FC.FEATURES, bit);
|
||||
}
|
||||
|
||||
for (const bit of toUnset) {
|
||||
FEATURES = bit_clear(FEATURES, bit);
|
||||
FC.FEATURES = BitHelper.bit_clear(FC.FEATURES, bit);
|
||||
}
|
||||
|
||||
mspHelper.saveFeatures(exitPoint);
|
||||
|
|
|
@ -2,7 +2,6 @@
|
|||
|
||||
const CONFIGURATOR = require('./data_storage');
|
||||
const Switchery = require('./libraries/switchery/switchery')
|
||||
const jBox = require('./libraries/jbox/jBox.min.js')
|
||||
const MSP = require('./msp');
|
||||
const FC = require('./fc');
|
||||
const interval = require('./intervals');
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
'use strict';
|
||||
|
||||
// From Betaflight
|
||||
// Thanks to Betaflight :)
|
||||
|
||||
window.$ = window.jQuery = require('jquery');
|
||||
const { app } = require('@electron/remote');
|
||||
|
|
|
@ -1,6 +1,8 @@
|
|||
/*global $,FC*/
|
||||
'use strict';
|
||||
|
||||
const FC = require('./fc');
|
||||
const { GUI } = require('./../js/gui');
|
||||
|
||||
let LogicCondition = function (enabled, activatorId, operation, operandAType, operandAValue, operandBType, operandBValue, flags) {
|
||||
let self = {};
|
||||
let $row;
|
||||
|
@ -316,3 +318,5 @@ let LogicCondition = function (enabled, activatorId, operation, operandAType, op
|
|||
|
||||
return self;
|
||||
};
|
||||
|
||||
module.exports = LogicCondition;
|
|
@ -11,7 +11,6 @@ const usbBootloaderIds = [
|
|||
{ vendorId: 11836, productId: 57105}
|
||||
];
|
||||
|
||||
|
||||
// Handle creating/removing shortcuts on Windows when installing/uninstalling.
|
||||
if (require('electron-squirrel-startup')) {
|
||||
app.quit();
|
||||
|
@ -22,7 +21,7 @@ let bluetoothDeviceChooser = null;
|
|||
let btDeviceList = null;
|
||||
let selectBluetoothCallback = null;
|
||||
|
||||
// In Eletrcon the bluetooth device chooser didn't exist, so we have to buid our own
|
||||
// In Eletrcon the bluetooth device chooser didn't exist, so we have to build our own
|
||||
function createDeviceChooser() {
|
||||
bluetoothDeviceChooser = new BrowserWindow({
|
||||
parent: mainWindow,
|
||||
|
|
|
@ -23,10 +23,10 @@ const SERVO = {
|
|||
}
|
||||
|
||||
const INPUT = {
|
||||
STABILIZED_DROLL: 0,
|
||||
STABILIZED_ROLL: 0,
|
||||
STABILIZED_PITCH: 1,
|
||||
STABILIZED_YAW: 2,
|
||||
THROTTLE: 3,
|
||||
STABILIZED_THROTTLE: 3,
|
||||
RC_ROLL: 4,
|
||||
RC_PITCH: 5,
|
||||
RC_YAW: 6,
|
||||
|
@ -37,7 +37,7 @@ const INPUT = {
|
|||
RC_AUX4: 11,
|
||||
GIMBAL_PITCH: 12,
|
||||
GIMBAL_ROLL: 13,
|
||||
FEATURE_FLAPS: 14,
|
||||
FEATURE_FLAPS: 14
|
||||
}
|
||||
|
||||
const STABILIZED = {
|
||||
|
|
|
@ -1,6 +1,7 @@
|
|||
/*global $,constrain*/
|
||||
'use strict';
|
||||
|
||||
const { constrain } = require('./helpers')
|
||||
|
||||
var MotorMixRule = function (throttle, roll, pitch, yaw) {
|
||||
|
||||
var self = {};
|
||||
|
|
|
@ -9,6 +9,10 @@ const MSP = require('./../msp');
|
|||
const MSPCodes = require('./MSPCodes');
|
||||
const FC = require('./../fc');
|
||||
const mspQueue = require('./../serial_queue');
|
||||
const ServoMixRule = require('./../servoMixRule');
|
||||
const MotorMixRule = require('./../motorMixRule');
|
||||
const LogicCondition = require('./../logicCondition');
|
||||
const BitHelper = require('../bitHelper');
|
||||
|
||||
var mspHelper = (function () {
|
||||
var self = {};
|
||||
|
@ -178,7 +182,7 @@ var mspHelper = (function () {
|
|||
case MSPCodes.MSP_RC:
|
||||
FC.RC.active_channels = dataHandler.message_length_expected / 2;
|
||||
|
||||
for (let i = 0; i < RC.active_channels; i++) {
|
||||
for (let i = 0; i < FC.RC.active_channels; i++) {
|
||||
FC.RC.channels[i] = data.getUint16((i * 2), true);
|
||||
}
|
||||
break;
|
||||
|
@ -1698,29 +1702,29 @@ var mspHelper = (function () {
|
|||
switch (code) {
|
||||
|
||||
case MSPCodes.MSP_SET_FEATURE:
|
||||
buffer.push(specificByte(FC.FEATURESS, 0));
|
||||
buffer.push(specificByte(FC.FEATURESS, 1));
|
||||
buffer.push(specificByte(FC.FEATURESS, 2));
|
||||
buffer.push(specificByte(FC.FEATURESS, 3));
|
||||
buffer.push(BitHelper.specificByte(FC.FEATURESS, 0));
|
||||
buffer.push(BitHelper.specificByte(FC.FEATURESS, 1));
|
||||
buffer.push(BitHelper.specificByte(FC.FEATURESS, 2));
|
||||
buffer.push(BitHelper.specificByte(FC.FEATURESS, 3));
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_SET_BOARD_ALIGNMENT:
|
||||
buffer.push(specificByte(FC.BOARD_ALIGNMENT.roll, 0));
|
||||
buffer.push(specificByte(FC.BOARD_ALIGNMENT.roll, 1));
|
||||
buffer.push(specificByte(FC.BOARD_ALIGNMENT.pitch, 0));
|
||||
buffer.push(specificByte(FC.BOARD_ALIGNMENT.pitch, 1));
|
||||
buffer.push(specificByte(FC.BOARD_ALIGNMENT.yaw, 0));
|
||||
buffer.push(specificByte(FC.BOARD_ALIGNMENT.yaw, 1));
|
||||
buffer.push(BitHelper.specificByte(FC.BOARD_ALIGNMENT.roll, 0));
|
||||
buffer.push(BitHelper.specificByte(FC.BOARD_ALIGNMENT.roll, 1));
|
||||
buffer.push(BitHelper.specificByte(FC.BOARD_ALIGNMENT.pitch, 0));
|
||||
buffer.push(BitHelper.specificByte(FC.BOARD_ALIGNMENT.pitch, 1));
|
||||
buffer.push(BitHelper.specificByte(FC.BOARD_ALIGNMENT.yaw, 0));
|
||||
buffer.push(BitHelper.specificByte(FC.BOARD_ALIGNMENT.yaw, 1));
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_SET_CURRENT_METER_CONFIG:
|
||||
buffer.push(specificByte(FC.CURRENT_METER_CONFIG.scale, 0));
|
||||
buffer.push(specificByte(FC.CURRENT_METER_CONFIG.scale, 1));
|
||||
buffer.push(specificByte(FC.CURRENT_METER_CONFIG.offset, 0));
|
||||
buffer.push(specificByte(FC.CURRENT_METER_CONFIG.offset, 1));
|
||||
buffer.push(BitHelper.specificByte(FC.CURRENT_METER_CONFIG.scale, 0));
|
||||
buffer.push(BitHelper.specificByte(FC.CURRENT_METER_CONFIG.scale, 1));
|
||||
buffer.push(BitHelper.specificByte(FC.CURRENT_METER_CONFIG.offset, 0));
|
||||
buffer.push(BitHelper.specificByte(FC.CURRENT_METER_CONFIG.offset, 1));
|
||||
buffer.push(FC.CURRENT_METER_CONFIG.type);
|
||||
buffer.push(specificByte(FC.CURRENT_METER_CONFIG.capacity, 0));
|
||||
buffer.push(specificByte(FC.CURRENT_METER_CONFIG.capacity, 1));
|
||||
buffer.push(BitHelper.specificByte(FC.CURRENT_METER_CONFIG.capacity, 0));
|
||||
buffer.push(BitHelper.specificByte(FC.CURRENT_METER_CONFIG.capacity, 1));
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_SET_VTX_CONFIG:
|
||||
|
@ -1752,8 +1756,8 @@ var mspHelper = (function () {
|
|||
buffer.push(FC.RC_tuning.dynamic_THR_PID);
|
||||
buffer.push(Math.round(FC.RC_tuning.throttle_MID * 100));
|
||||
buffer.push(Math.round(FC.RC_tuning.throttle_EXPO * 100));
|
||||
buffer.push(lowByte(FC.RC_tuning.dynamic_THR_breakpoint));
|
||||
buffer.push(highByte(FC.RC_tuning.dynamic_THR_breakpoint));
|
||||
buffer.push(BitHelper.lowByte(FC.RC_tuning.dynamic_THR_breakpoint));
|
||||
buffer.push(BitHelper.highByte(FC.RC_tuning.dynamic_THR_breakpoint));
|
||||
buffer.push(Math.round(FC.RC_tuning.RC_YAW_EXPO * 100));
|
||||
break;
|
||||
case MSPCodes.MSPV2_INAV_SET_RATE_PROFILE:
|
||||
|
@ -1761,8 +1765,8 @@ var mspHelper = (function () {
|
|||
buffer.push(Math.round(FC.RC_tuning.throttle_MID * 100));
|
||||
buffer.push(Math.round(FC.RC_tuning.throttle_EXPO * 100));
|
||||
buffer.push(FC.RC_tuning.dynamic_THR_PID);
|
||||
buffer.push(lowByte(FC.RC_tuning.dynamic_THR_breakpoint));
|
||||
buffer.push(highByte(FC.RC_tuning.dynamic_THR_breakpoint));
|
||||
buffer.push(BitHelper.lowByte(FC.RC_tuning.dynamic_THR_breakpoint));
|
||||
buffer.push(BitHelper.highByte(FC.RC_tuning.dynamic_THR_breakpoint));
|
||||
|
||||
// stabilized
|
||||
buffer.push(Math.round(FC.RC_tuning.RC_EXPO * 100));
|
||||
|
@ -1785,119 +1789,119 @@ var mspHelper = (function () {
|
|||
}
|
||||
break;
|
||||
case MSPCodes.MSP_SET_ACC_TRIM:
|
||||
buffer.push(lowByte(FC.CONFIG.accelerometerTrims[0]));
|
||||
buffer.push(highByte(FC.CONFIG.accelerometerTrims[0]));
|
||||
buffer.push(lowByte(FC.CONFIG.accelerometerTrims[1]));
|
||||
buffer.push(highByte(FC.CONFIG.accelerometerTrims[1]));
|
||||
buffer.push(BitHelper.lowByte(FC.CONFIG.accelerometerTrims[0]));
|
||||
buffer.push(BitHelper.highByte(FC.CONFIG.accelerometerTrims[0]));
|
||||
buffer.push(BitHelper.lowByte(FC.CONFIG.accelerometerTrims[1]));
|
||||
buffer.push(BitHelper.highByte(FC.CONFIG.accelerometerTrims[1]));
|
||||
break;
|
||||
case MSPCodes.MSP_SET_ARMING_CONFIG:
|
||||
buffer.push(FC.ARMING_CONFIG.auto_disarm_delay);
|
||||
buffer.push(FC.ARMING_CONFIG.disarm_kill_switch);
|
||||
break;
|
||||
case MSPCodes.MSP_SET_LOOP_TIME:
|
||||
buffer.push(lowByte(FC.FC_CONFIG.loopTime));
|
||||
buffer.push(highByte(FC.FC_CONFIG.loopTime));
|
||||
buffer.push(BitHelper.lowByte(FC.FC_CONFIG.loopTime));
|
||||
buffer.push(BitHelper.highByte(FC.FC_CONFIG.loopTime));
|
||||
break;
|
||||
case MSPCodes.MSP_SET_MISC:
|
||||
buffer.push(lowByte(FC.MISC.midrc));
|
||||
buffer.push(highByte(FC.MISC.midrc));
|
||||
buffer.push(lowByte(FC.MISC.minthrottle));
|
||||
buffer.push(highByte(FC.MISC.minthrottle));
|
||||
buffer.push(lowByte(FC.MISC.maxthrottle));
|
||||
buffer.push(highByte(FC.MISC.maxthrottle));
|
||||
buffer.push(lowByte(FC.MISC.mincommand));
|
||||
buffer.push(highByte(FC.MISC.mincommand));
|
||||
buffer.push(lowByte(FC.MISC.failsafe_throttle));
|
||||
buffer.push(highByte(FC.MISC.failsafe_throttle));
|
||||
buffer.push(BitHelper.lowByte(FC.MISC.midrc));
|
||||
buffer.push(BitHelper.highByte(FC.MISC.midrc));
|
||||
buffer.push(BitHelper.lowByte(FC.MISC.minthrottle));
|
||||
buffer.push(BitHelper.highByte(FC.MISC.minthrottle));
|
||||
buffer.push(BitHelper.lowByte(FC.MISC.maxthrottle));
|
||||
buffer.push(BitHelper.highByte(FC.MISC.maxthrottle));
|
||||
buffer.push(BitHelper.lowByte(FC.MISC.mincommand));
|
||||
buffer.push(BitHelper.highByte(FC.MISC.mincommand));
|
||||
buffer.push(BitHelper.lowByte(FC.MISC.failsafe_throttle));
|
||||
buffer.push(BitHelper.highByte(FC.MISC.failsafe_throttle));
|
||||
buffer.push(FC.MISC.gps_type);
|
||||
buffer.push(FC.MISC.sensors_baudrate);
|
||||
buffer.push(FC.MISC.gps_ubx_sbas);
|
||||
buffer.push(FC.MISC.multiwiicurrentoutput);
|
||||
buffer.push(FC.MISC.rssi_channel);
|
||||
buffer.push(FC.MISC.placeholder2);
|
||||
buffer.push(lowByte(Math.round(FC.MISC.mag_declination * 10)));
|
||||
buffer.push(highByte(Math.round(FC.MISC.mag_declination * 10)));
|
||||
buffer.push(BitHelper.lowByte(Math.round(FC.MISC.mag_declination * 10)));
|
||||
buffer.push(BitHelper.highByte(Math.round(FC.MISC.mag_declination * 10)));
|
||||
buffer.push(FC.MISC.vbatscale);
|
||||
buffer.push(Math.round(FC.MISC.vbatmincellvoltage * 10));
|
||||
buffer.push(Math.round(FC.MISC.vbatmaxcellvoltage * 10));
|
||||
buffer.push(Math.round(FC.MISC.vbatwarningcellvoltage * 10));
|
||||
break;
|
||||
case MSPCodes.MSPV2_INAV_SET_MISC:
|
||||
buffer.push(lowByte(FC.MISC.midrc));
|
||||
buffer.push(highByte(FC.MISC.midrc));
|
||||
buffer.push(lowByte(FC.MISC.minthrottle));
|
||||
buffer.push(highByte(FC.MISC.minthrottle));
|
||||
buffer.push(lowByte(FC.MISC.maxthrottle));
|
||||
buffer.push(highByte(FC.MISC.maxthrottle));
|
||||
buffer.push(lowByte(FC.MISC.mincommand));
|
||||
buffer.push(highByte(FC.MISC.mincommand));
|
||||
buffer.push(lowByte(FC.MISC.failsafe_throttle));
|
||||
buffer.push(highByte(FC.MISC.failsafe_throttle));
|
||||
buffer.push(BitHelper.lowByte(FC.MISC.midrc));
|
||||
buffer.push(BitHelper.highByte(FC.MISC.midrc));
|
||||
buffer.push(BitHelper.lowByte(FC.MISC.minthrottle));
|
||||
buffer.push(BitHelper.highByte(FC.MISC.minthrottle));
|
||||
buffer.push(BitHelper.lowByte(FC.MISC.maxthrottle));
|
||||
buffer.push(BitHelper.highByte(FC.MISC.maxthrottle));
|
||||
buffer.push(BitHelper.lowByte(FC.MISC.mincommand));
|
||||
buffer.push(BitHelper.highByte(FC.MISC.mincommand));
|
||||
buffer.push(BitHelper.lowByte(FC.MISC.failsafe_throttle));
|
||||
buffer.push(BitHelper.highByte(FC.MISC.failsafe_throttle));
|
||||
buffer.push(FC.MISC.gps_type);
|
||||
buffer.push(FC.MISC.sensors_baudrate);
|
||||
buffer.push(FC.MISC.gps_ubx_sbas);
|
||||
buffer.push(FC.MISC.rssi_channel);
|
||||
buffer.push(lowByte(Math.round(FC.MISC.mag_declination * 10)));
|
||||
buffer.push(highByte(Math.round(FC.MISC.mag_declination * 10)));
|
||||
buffer.push(lowByte(FC.MISC.vbatscale));
|
||||
buffer.push(highByte(FC.MISC.vbatscale));
|
||||
buffer.push(BitHelper.lowByte(Math.round(FC.MISC.mag_declination * 10)));
|
||||
buffer.push(BitHelper.highByte(Math.round(FC.MISC.mag_declination * 10)));
|
||||
buffer.push(BitHelper.lowByte(FC.MISC.vbatscale));
|
||||
buffer.push(BitHelper.highByte(FC.MISC.vbatscale));
|
||||
buffer.push(FC.MISC.voltage_source);
|
||||
buffer.push(FC.MISC.battery_cells);
|
||||
buffer.push(lowByte(Math.round(FC.MISC.vbatdetectcellvoltage * 100)));
|
||||
buffer.push(highByte(Math.round(FC.MISC.vbatdetectcellvoltage * 100)));
|
||||
buffer.push(lowByte(Math.round(FC.MISC.vbatmincellvoltage * 100)));
|
||||
buffer.push(highByte(Math.round(FC.MISC.vbatmincellvoltage * 100)));
|
||||
buffer.push(lowByte(Math.round(FC.MISC.vbatmaxcellvoltage * 100)));
|
||||
buffer.push(highByte(Math.round(FC.MISC.vbatmaxcellvoltage * 100)));
|
||||
buffer.push(lowByte(Math.round(FC.MISC.vbatwarningcellvoltage * 100)));
|
||||
buffer.push(highByte(Math.round(FC.MISC.vbatwarningcellvoltage * 100)));
|
||||
buffer.push(BitHelper.lowByte(Math.round(FC.MISC.vbatdetectcellvoltage * 100)));
|
||||
buffer.push(BitHelper.highByte(Math.round(FC.MISC.vbatdetectcellvoltage * 100)));
|
||||
buffer.push(BitHelper.lowByte(Math.round(FC.MISC.vbatmincellvoltage * 100)));
|
||||
buffer.push(BitHelper.highByte(Math.round(FC.MISC.vbatmincellvoltage * 100)));
|
||||
buffer.push(BitHelper.lowByte(Math.round(FC.MISC.vbatmaxcellvoltage * 100)));
|
||||
buffer.push(BitHelper.highByte(Math.round(FC.MISC.vbatmaxcellvoltage * 100)));
|
||||
buffer.push(BitHelper.lowByte(Math.round(FC.MISC.vbatwarningcellvoltage * 100)));
|
||||
buffer.push(BitHelper.highByte(Math.round(FC.MISC.vbatwarningcellvoltage * 100)));
|
||||
for (let byte_index = 0; byte_index < 4; ++byte_index)
|
||||
buffer.push(specificByte(FC.MISC.battery_capacity, byte_index));
|
||||
buffer.push(BitHelper.specificByte(FC.MISC.battery_capacity, byte_index));
|
||||
for (let byte_index = 0; byte_index < 4; ++byte_index)
|
||||
buffer.push(specificByte(FC.MISC.battery_capacity_warning, byte_index));
|
||||
buffer.push(BitHelper.specificByte(FC.MISC.battery_capacity_warning, byte_index));
|
||||
for (let byte_index = 0; byte_index < 4; ++byte_index)
|
||||
buffer.push(specificByte(FC.MISC.battery_capacity_critical, byte_index));
|
||||
buffer.push(BitHelper.specificByte(FC.MISC.battery_capacity_critical, byte_index));
|
||||
buffer.push((FC.MISC.battery_capacity_unit == 'mAh') ? 0 : 1);
|
||||
break;
|
||||
case MSPCodes.MSPV2_INAV_SET_BATTERY_CONFIG:
|
||||
buffer.push(lowByte(FC.BATTERY_CONFIG.vbatscale));
|
||||
buffer.push(highByte(FC.BATTERY_CONFIG.vbatscale));
|
||||
buffer.push(BitHelper.lowByte(FC.BATTERY_CONFIG.vbatscale));
|
||||
buffer.push(BitHelper.highByte(FC.BATTERY_CONFIG.vbatscale));
|
||||
buffer.push(FC.BATTERY_CONFIG.voltage_source);
|
||||
buffer.push(FC.BATTERY_CONFIG.battery_cells);
|
||||
buffer.push(lowByte(Math.round(FC.BATTERY_CONFIG.vbatdetectcellvoltage * 100)));
|
||||
buffer.push(highByte(Math.round(FC.BATTERY_CONFIG.vbatdetectcellvoltage * 100)));
|
||||
buffer.push(lowByte(Math.round(FC.BATTERY_CONFIG.vbatmincellvoltage * 100)));
|
||||
buffer.push(highByte(Math.round(FC.BATTERY_CONFIG.vbatmincellvoltage * 100)));
|
||||
buffer.push(lowByte(Math.round(FC.BATTERY_CONFIG.vbatmaxcellvoltage * 100)));
|
||||
buffer.push(highByte(Math.round(FC.BATTERY_CONFIG.vbatmaxcellvoltage * 100)));
|
||||
buffer.push(lowByte(Math.round(FC.BATTERY_CONFIG.vbatwarningcellvoltage * 100)));
|
||||
buffer.push(highByte(Math.round(FC.BATTERY_CONFIG.vbatwarningcellvoltage * 100)));
|
||||
buffer.push(lowByte(FC.BATTERY_CONFIG.current_offset));
|
||||
buffer.push(highByte(FC.BATTERY_CONFIG.current_offset));
|
||||
buffer.push(lowByte(FC.BATTERY_CONFIG.current_scale));
|
||||
buffer.push(highByte(FC.BATTERY_CONFIG.current_scale));
|
||||
buffer.push(BitHelper.lowByte(Math.round(FC.BATTERY_CONFIG.vbatdetectcellvoltage * 100)));
|
||||
buffer.push(BitHelper.highByte(Math.round(FC.BATTERY_CONFIG.vbatdetectcellvoltage * 100)));
|
||||
buffer.push(BitHelper.lowByte(Math.round(FC.BATTERY_CONFIG.vbatmincellvoltage * 100)));
|
||||
buffer.push(BitHelper.highByte(Math.round(FC.BATTERY_CONFIG.vbatmincellvoltage * 100)));
|
||||
buffer.push(BitHelper.lowByte(Math.round(FC.BATTERY_CONFIG.vbatmaxcellvoltage * 100)));
|
||||
buffer.push(BitHelper.highByte(Math.round(FC.BATTERY_CONFIG.vbatmaxcellvoltage * 100)));
|
||||
buffer.push(BitHelper.lowByte(Math.round(FC.BATTERY_CONFIG.vbatwarningcellvoltage * 100)));
|
||||
buffer.push(BitHelper.highByte(Math.round(FC.BATTERY_CONFIG.vbatwarningcellvoltage * 100)));
|
||||
buffer.push(BitHelper.lowByte(FC.BATTERY_CONFIG.current_offset));
|
||||
buffer.push(BitHelper.highByte(FC.BATTERY_CONFIG.current_offset));
|
||||
buffer.push(BitHelper.lowByte(FC.BATTERY_CONFIG.current_scale));
|
||||
buffer.push(BitHelper.highByte(FC.BATTERY_CONFIG.current_scale));
|
||||
for (let byte_index = 0; byte_index < 4; ++byte_index)
|
||||
buffer.push(specificByte(FC.BATTERY_CONFIG.capacity, byte_index));
|
||||
buffer.push(BitHelper.specificByte(FC.BATTERY_CONFIG.capacity, byte_index));
|
||||
for (let byte_index = 0; byte_index < 4; ++byte_index)
|
||||
buffer.push(specificByte(FC.BATTERY_CONFIG.capacity_warning, byte_index));
|
||||
buffer.push(BitHelper.specificByte(FC.BATTERY_CONFIG.capacity_warning, byte_index));
|
||||
for (let byte_index = 0; byte_index < 4; ++byte_index)
|
||||
buffer.push(specificByte(FC.BATTERY_CONFIG.capacity_critical, byte_index));
|
||||
buffer.push(BitHelper.specificByte(FC.BATTERY_CONFIG.capacity_critical, byte_index));
|
||||
buffer.push(FC.BATTERY_CONFIG.capacity_unit);
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_SET_RX_CONFIG:
|
||||
buffer.push(FC.RX_CONFIG.serialrx_provider);
|
||||
buffer.push(lowByte(FC.RX_CONFIG.maxcheck));
|
||||
buffer.push(highByte(FC.RX_CONFIG.maxcheck));
|
||||
buffer.push(lowByte(FC.RX_CONFIG.midrc));
|
||||
buffer.push(highByte(FC.RX_CONFIG.midrc));
|
||||
buffer.push(lowByte(FC.RX_CONFIG.mincheck));
|
||||
buffer.push(highByte(FC.RX_CONFIG.mincheck));
|
||||
buffer.push(BitHelper.lowByte(FC.RX_CONFIG.maxcheck));
|
||||
buffer.push(BitHelper.highByte(FC.RX_CONFIG.maxcheck));
|
||||
buffer.push(BitHelper.lowByte(FC.RX_CONFIG.midrc));
|
||||
buffer.push(BitHelper.highByte(FC.RX_CONFIG.midrc));
|
||||
buffer.push(BitHelper.lowByte(FC.RX_CONFIG.mincheck));
|
||||
buffer.push(BitHelper.highByte(FC.RX_CONFIG.mincheck));
|
||||
buffer.push(FC.RX_CONFIG.spektrum_sat_bind);
|
||||
buffer.push(lowByte(FC.RX_CONFIG.rx_min_usec));
|
||||
buffer.push(highByte(FC.RX_CONFIG.rx_min_usec));
|
||||
buffer.push(lowByte(FC.RX_CONFIG.rx_max_usec));
|
||||
buffer.push(highByte(FC.RX_CONFIG.rx_max_usec));
|
||||
buffer.push(BitHelper.lowByte(FC.RX_CONFIG.rx_min_usec));
|
||||
buffer.push(BitHelper.highByte(FC.RX_CONFIG.rx_min_usec));
|
||||
buffer.push(BitHelper.lowByte(FC.RX_CONFIG.rx_max_usec));
|
||||
buffer.push(BitHelper.highByte(FC.RX_CONFIG.rx_max_usec));
|
||||
buffer.push(0); // 4 null bytes for betaflight compatibility
|
||||
buffer.push(0);
|
||||
buffer.push(0);
|
||||
|
@ -1915,23 +1919,23 @@ var mspHelper = (function () {
|
|||
case MSPCodes.MSP_SET_FAILSAFE_CONFIG:
|
||||
buffer.push(FC.FAILSAFE_CONFIG.failsafe_delay);
|
||||
buffer.push(FC.FAILSAFE_CONFIG.failsafe_off_delay);
|
||||
buffer.push(lowByte(FC.FAILSAFE_CONFIG.failsafe_throttle));
|
||||
buffer.push(highByte(FC.FAILSAFE_CONFIG.failsafe_throttle));
|
||||
buffer.push(BitHelper.lowByte(FC.FAILSAFE_CONFIG.failsafe_throttle));
|
||||
buffer.push(BitHelper.highByte(FC.FAILSAFE_CONFIG.failsafe_throttle));
|
||||
buffer.push(FC.FAILSAFE_CONFIG.failsafe_kill_switch);
|
||||
buffer.push(lowByte(FC.FAILSAFE_CONFIG.failsafe_throttle_low_delay));
|
||||
buffer.push(highByte(FC.FAILSAFE_CONFIG.failsafe_throttle_low_delay));
|
||||
buffer.push(BitHelper.lowByte(FC.FAILSAFE_CONFIG.failsafe_throttle_low_delay));
|
||||
buffer.push(BitHelper.highByte(FC.FAILSAFE_CONFIG.failsafe_throttle_low_delay));
|
||||
buffer.push(FC.FAILSAFE_CONFIG.failsafe_procedure);
|
||||
buffer.push(FC.FAILSAFE_CONFIG.failsafe_recovery_delay);
|
||||
buffer.push(lowByte(FC.FAILSAFE_CONFIG.failsafe_fw_roll_angle));
|
||||
buffer.push(highByte(FC.FAILSAFE_CONFIG.failsafe_fw_roll_angle));
|
||||
buffer.push(lowByte(FC.FAILSAFE_CONFIG.failsafe_fw_pitch_angle));
|
||||
buffer.push(highByte(FC.FAILSAFE_CONFIG.failsafe_fw_pitch_angle));
|
||||
buffer.push(lowByte(FC.FAILSAFE_CONFIG.failsafe_fw_yaw_rate));
|
||||
buffer.push(highByte(FC.FAILSAFE_CONFIG.failsafe_fw_yaw_rate));
|
||||
buffer.push(lowByte(FC.FAILSAFE_CONFIG.failsafe_stick_motion_threshold));
|
||||
buffer.push(highByte(FC.FAILSAFE_CONFIG.failsafe_stick_motion_threshold));
|
||||
buffer.push(lowByte(FC.FAILSAFE_CONFIG.failsafe_min_distance));
|
||||
buffer.push(highByte(FC.FAILSAFE_CONFIG.failsafe_min_distance));
|
||||
buffer.push(BitHelper.lowByte(FC.FAILSAFE_CONFIG.failsafe_fw_roll_angle));
|
||||
buffer.push(BitHelper.highByte(FC.FAILSAFE_CONFIG.failsafe_fw_roll_angle));
|
||||
buffer.push(BitHelper.lowByte(FC.FAILSAFE_CONFIG.failsafe_fw_pitch_angle));
|
||||
buffer.push(BitHelper.highByte(FC.FAILSAFE_CONFIG.failsafe_fw_pitch_angle));
|
||||
buffer.push(BitHelper.lowByte(FC.FAILSAFE_CONFIG.failsafe_fw_yaw_rate));
|
||||
buffer.push(BitHelper.highByte(FC.FAILSAFE_CONFIG.failsafe_fw_yaw_rate));
|
||||
buffer.push(BitHelper.lowByte(FC.FAILSAFE_CONFIG.failsafe_stick_motion_threshold));
|
||||
buffer.push(BitHelper.highByte(FC.FAILSAFE_CONFIG.failsafe_stick_motion_threshold));
|
||||
buffer.push(BitHelper.lowByte(FC.FAILSAFE_CONFIG.failsafe_min_distance));
|
||||
buffer.push(BitHelper.highByte(FC.FAILSAFE_CONFIG.failsafe_min_distance));
|
||||
buffer.push(FC.FAILSAFE_CONFIG.failsafe_min_distance_procedure);
|
||||
break;
|
||||
|
||||
|
@ -1952,10 +1956,10 @@ var mspHelper = (function () {
|
|||
buffer.push(serialPort.identifier);
|
||||
|
||||
var functionMask = mspHelper.SERIAL_PORT_FUNCTIONSToMask(serialPort.functions);
|
||||
buffer.push(specificByte(functionMask, 0));
|
||||
buffer.push(specificByte(functionMask, 1));
|
||||
buffer.push(specificByte(functionMask, 2));
|
||||
buffer.push(specificByte(functionMask, 3));
|
||||
buffer.push(BitHelper.specificByte(functionMask, 0));
|
||||
buffer.push(BitHelper.specificByte(functionMask, 1));
|
||||
buffer.push(BitHelper.specificByte(functionMask, 2));
|
||||
buffer.push(BitHelper.specificByte(functionMask, 3));
|
||||
|
||||
var BAUD_RATES = mspHelper.BAUD_RATES_post1_6_3;
|
||||
buffer.push(BAUD_RATES.indexOf(serialPort.msp_baudrate));
|
||||
|
@ -1966,20 +1970,20 @@ var mspHelper = (function () {
|
|||
break;
|
||||
|
||||
case MSPCodes.MSP_SET_3D:
|
||||
buffer.push(lowByte(FC.REVERSIBLE_MOTORS.deadband_low));
|
||||
buffer.push(highByte(FC.REVERSIBLE_MOTORS.deadband_low));
|
||||
buffer.push(lowByte(FC.REVERSIBLE_MOTORS.deadband_high));
|
||||
buffer.push(highByte(FC.REVERSIBLE_MOTORS.deadband_high));
|
||||
buffer.push(lowByte(FC.REVERSIBLE_MOTORS.neutral));
|
||||
buffer.push(highByte(FC.REVERSIBLE_MOTORS.neutral));
|
||||
buffer.push(BitHelper.lowByte(FC.REVERSIBLE_MOTORS.deadband_low));
|
||||
buffer.push(BitHelper.highByte(FC.REVERSIBLE_MOTORS.deadband_low));
|
||||
buffer.push(BitHelper.lowByte(FC.REVERSIBLE_MOTORS.deadband_high));
|
||||
buffer.push(BitHelper.highByte(FC.REVERSIBLE_MOTORS.deadband_high));
|
||||
buffer.push(BitHelper.lowByte(FC.REVERSIBLE_MOTORS.neutral));
|
||||
buffer.push(BitHelper.highByte(FC.REVERSIBLE_MOTORS.neutral));
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_SET_RC_DEADBAND:
|
||||
buffer.push(FC.RC_deadband.deadband);
|
||||
buffer.push(FC.RC_deadband.yaw_deadband);
|
||||
buffer.push(FC.RC_deadband.alt_hold_deadband);
|
||||
buffer.push(lowByte(FC.REVERSIBLE_MOTORS.deadband_throttle));
|
||||
buffer.push(highByte(FC.REVERSIBLE_MOTORS.deadband_throttle));
|
||||
buffer.push(BitHelper.lowByte(FC.REVERSIBLE_MOTORS.deadband_throttle));
|
||||
buffer.push(BitHelper.highByte(FC.REVERSIBLE_MOTORS.deadband_throttle));
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_SET_SENSOR_ALIGNMENT:
|
||||
|
@ -1995,11 +1999,11 @@ var mspHelper = (function () {
|
|||
buffer.push(FC.ADVANCED_CONFIG.useUnsyncedPwm);
|
||||
buffer.push(FC.ADVANCED_CONFIG.motorPwmProtocol);
|
||||
|
||||
buffer.push(lowByte(FC.ADVANCED_CONFIG.motorPwmRate));
|
||||
buffer.push(highByte(FC.ADVANCED_CONFIG.motorPwmRate));
|
||||
buffer.push(BitHelper.lowByte(FC.ADVANCED_CONFIG.motorPwmRate));
|
||||
buffer.push(BitHelper.highByte(FC.ADVANCED_CONFIG.motorPwmRate));
|
||||
|
||||
buffer.push(lowByte(FC.ADVANCED_CONFIG.servoPwmRate));
|
||||
buffer.push(highByte(FC.ADVANCED_CONFIG.servoPwmRate));
|
||||
buffer.push(BitHelper.lowByte(FC.ADVANCED_CONFIG.servoPwmRate));
|
||||
buffer.push(BitHelper.highByte(FC.ADVANCED_CONFIG.servoPwmRate));
|
||||
|
||||
buffer.push(FC.ADVANCED_CONFIG.gyroSync);
|
||||
break;
|
||||
|
@ -2007,17 +2011,17 @@ var mspHelper = (function () {
|
|||
case MSPCodes.MSP_SET_INAV_PID:
|
||||
buffer.push(FC.INAV_PID_CONFIG.asynchronousMode);
|
||||
|
||||
buffer.push(lowByte(FC.INAV_PID_CONFIG.accelerometerTaskFrequency));
|
||||
buffer.push(highByte(FC.INAV_PID_CONFIG.accelerometerTaskFrequency));
|
||||
buffer.push(BitHelper.lowByte(FC.INAV_PID_CONFIG.accelerometerTaskFrequency));
|
||||
buffer.push(BitHelper.highByte(FC.INAV_PID_CONFIG.accelerometerTaskFrequency));
|
||||
|
||||
buffer.push(lowByte(FC.INAV_PID_CONFIG.attitudeTaskFrequency));
|
||||
buffer.push(highByte(FC.INAV_PID_CONFIG.attitudeTaskFrequency));
|
||||
buffer.push(BitHelper.lowByte(FC.INAV_PID_CONFIG.attitudeTaskFrequency));
|
||||
buffer.push(BitHelper.highByte(FC.INAV_PID_CONFIG.attitudeTaskFrequency));
|
||||
|
||||
buffer.push(FC.INAV_PID_CONFIG.magHoldRateLimit);
|
||||
buffer.push(FC.INAV_PID_CONFIG.magHoldErrorLpfFrequency);
|
||||
|
||||
buffer.push(lowByte(FC.INAV_PID_CONFIG.yawJumpPreventionLimit));
|
||||
buffer.push(highByte(FC.INAV_PID_CONFIG.yawJumpPreventionLimit));
|
||||
buffer.push(BitHelper.lowByte(FC.INAV_PID_CONFIG.yawJumpPreventionLimit));
|
||||
buffer.push(BitHelper.highByte(FC.INAV_PID_CONFIG.yawJumpPreventionLimit));
|
||||
|
||||
buffer.push(FC.INAV_PID_CONFIG.gyroscopeLpf);
|
||||
buffer.push(FC.INAV_PID_CONFIG.accSoftLpfHz);
|
||||
|
@ -2031,91 +2035,91 @@ var mspHelper = (function () {
|
|||
case MSPCodes.MSP_SET_NAV_POSHOLD:
|
||||
buffer.push(FC.NAV_POSHOLD.userControlMode);
|
||||
|
||||
buffer.push(lowByte(FC.NAV_POSHOLD.maxSpeed));
|
||||
buffer.push(highByte(FC.NAV_POSHOLD.maxSpeed));
|
||||
buffer.push(BitHelper.lowByte(FC.NAV_POSHOLD.maxSpeed));
|
||||
buffer.push(BitHelper.highByte(FC.NAV_POSHOLD.maxSpeed));
|
||||
|
||||
buffer.push(lowByte(FC.NAV_POSHOLD.maxClimbRate));
|
||||
buffer.push(highByte(FC.NAV_POSHOLD.maxClimbRate));
|
||||
buffer.push(BitHelper.lowByte(FC.NAV_POSHOLD.maxClimbRate));
|
||||
buffer.push(BitHelper.highByte(FC.NAV_POSHOLD.maxClimbRate));
|
||||
|
||||
buffer.push(lowByte(FC.NAV_POSHOLD.maxManualSpeed));
|
||||
buffer.push(highByte(FC.NAV_POSHOLD.maxManualSpeed));
|
||||
buffer.push(BitHelper.lowByte(FC.NAV_POSHOLD.maxManualSpeed));
|
||||
buffer.push(BitHelper.highByte(FC.NAV_POSHOLD.maxManualSpeed));
|
||||
|
||||
buffer.push(lowByte(FC.NAV_POSHOLD.maxManualClimbRate));
|
||||
buffer.push(highByte(FC.NAV_POSHOLD.maxManualClimbRate));
|
||||
buffer.push(BitHelper.lowByte(FC.NAV_POSHOLD.maxManualClimbRate));
|
||||
buffer.push(BitHelper.highByte(FC.NAV_POSHOLD.maxManualClimbRate));
|
||||
|
||||
buffer.push(FC.NAV_POSHOLD.maxBankAngle);
|
||||
buffer.push(FC.NAV_POSHOLD.useThrottleMidForAlthold);
|
||||
|
||||
buffer.push(lowByte(FC.NAV_POSHOLD.hoverThrottle));
|
||||
buffer.push(highByte(FC.NAV_POSHOLD.hoverThrottle));
|
||||
buffer.push(BitHelper.lowByte(FC.NAV_POSHOLD.hoverThrottle));
|
||||
buffer.push(BitHelper.highByte(FC.NAV_POSHOLD.hoverThrottle));
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_SET_CALIBRATION_DATA:
|
||||
|
||||
buffer.push(lowByte(FC.CALIBRATION_DATA.accZero.X));
|
||||
buffer.push(highByte(FC.CALIBRATION_DATA.accZero.X));
|
||||
buffer.push(BitHelper.lowByte(FC.CALIBRATION_DATA.accZero.X));
|
||||
buffer.push(BitHelper.highByte(FC.CALIBRATION_DATA.accZero.X));
|
||||
|
||||
buffer.push(lowByte(FC.CALIBRATION_DATA.accZero.Y));
|
||||
buffer.push(highByte(FC.CALIBRATION_DATA.accZero.Y));
|
||||
buffer.push(BitHelper.lowByte(FC.CALIBRATION_DATA.accZero.Y));
|
||||
buffer.push(BitHelper.highByte(FC.CALIBRATION_DATA.accZero.Y));
|
||||
|
||||
buffer.push(lowByte(FC.CALIBRATION_DATA.accZero.Z));
|
||||
buffer.push(highByte(FC.CALIBRATION_DATA.accZero.Z));
|
||||
buffer.push(BitHelper.lowByte(FC.CALIBRATION_DATA.accZero.Z));
|
||||
buffer.push(BitHelper.highByte(FC.CALIBRATION_DATA.accZero.Z));
|
||||
|
||||
buffer.push(lowByte(FC.CALIBRATION_DATA.accGain.X));
|
||||
buffer.push(highByte(FC.CALIBRATION_DATA.accGain.X));
|
||||
buffer.push(BitHelper.lowByte(FC.CALIBRATION_DATA.accGain.X));
|
||||
buffer.push(BitHelper.highByte(FC.CALIBRATION_DATA.accGain.X));
|
||||
|
||||
buffer.push(lowByte(FC.CALIBRATION_DATA.accGain.Y));
|
||||
buffer.push(highByte(FC.CALIBRATION_DATA.accGain.Y));
|
||||
buffer.push(BitHelper.lowByte(FC.CALIBRATION_DATA.accGain.Y));
|
||||
buffer.push(BitHelper.highByte(FC.CALIBRATION_DATA.accGain.Y));
|
||||
|
||||
buffer.push(lowByte(FC.CALIBRATION_DATA.accGain.Z));
|
||||
buffer.push(highByte(FC.CALIBRATION_DATA.accGain.Z));
|
||||
buffer.push(BitHelper.lowByte(FC.CALIBRATION_DATA.accGain.Z));
|
||||
buffer.push(BitHelper.highByte(FC.CALIBRATION_DATA.accGain.Z));
|
||||
|
||||
buffer.push(lowByte(FC.CALIBRATION_DATA.magZero.X));
|
||||
buffer.push(highByte(FC.CALIBRATION_DATA.magZero.X));
|
||||
buffer.push(BitHelper.lowByte(FC.CALIBRATION_DATA.magZero.X));
|
||||
buffer.push(BitHelper.highByte(FC.CALIBRATION_DATA.magZero.X));
|
||||
|
||||
buffer.push(lowByte(FC.CALIBRATION_DATA.magZero.Y));
|
||||
buffer.push(highByte(FC.CALIBRATION_DATA.magZero.Y));
|
||||
buffer.push(BitHelper.lowByte(FC.CALIBRATION_DATA.magZero.Y));
|
||||
buffer.push(BitHelper.highByte(FC.CALIBRATION_DATA.magZero.Y));
|
||||
|
||||
buffer.push(lowByte(FC.CALIBRATION_DATA.magZero.Z));
|
||||
buffer.push(highByte(FC.CALIBRATION_DATA.magZero.Z));
|
||||
buffer.push(BitHelper.lowByte(FC.CALIBRATION_DATA.magZero.Z));
|
||||
buffer.push(BitHelper.highByte(FC.CALIBRATION_DATA.magZero.Z));
|
||||
|
||||
buffer.push(lowByte(Math.round(FC.CALIBRATION_DATA.opflow.Scale * 256)));
|
||||
buffer.push(highByte(Math.round(FC.CALIBRATION_DATA.opflow.Scale * 256)));
|
||||
buffer.push(BitHelper.lowByte(Math.round(FC.CALIBRATION_DATA.opflow.Scale * 256)));
|
||||
buffer.push(BitHelper.highByte(Math.round(FC.CALIBRATION_DATA.opflow.Scale * 256)));
|
||||
|
||||
buffer.push(lowByte(FC.CALIBRATION_DATA.magGain.X));
|
||||
buffer.push(highByte(FC.CALIBRATION_DATA.magGain.X));
|
||||
buffer.push(BitHelper.lowByte(FC.CALIBRATION_DATA.magGain.X));
|
||||
buffer.push(BitHelper.highByte(FC.CALIBRATION_DATA.magGain.X));
|
||||
|
||||
buffer.push(lowByte(FC.CALIBRATION_DATA.magGain.Y));
|
||||
buffer.push(highByte(FC.CALIBRATION_DATA.magGain.Y));
|
||||
buffer.push(BitHelper.lowByte(FC.CALIBRATION_DATA.magGain.Y));
|
||||
buffer.push(BitHelper.highByte(FC.CALIBRATION_DATA.magGain.Y));
|
||||
|
||||
buffer.push(lowByte(FC.CALIBRATION_DATA.magGain.Z));
|
||||
buffer.push(highByte(FC.CALIBRATION_DATA.magGain.Z));
|
||||
buffer.push(BitHelper.lowByte(FC.CALIBRATION_DATA.magGain.Z));
|
||||
buffer.push(BitHelper.highByte(FC.CALIBRATION_DATA.magGain.Z));
|
||||
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_SET_POSITION_ESTIMATION_CONFIG:
|
||||
buffer.push(lowByte(FC.POSITION_ESTIMATOR.w_z_baro_p * 100));
|
||||
buffer.push(highByte(FC.POSITION_ESTIMATOR.w_z_baro_p * 100));
|
||||
buffer.push(BitHelper.lowByte(FC.POSITION_ESTIMATOR.w_z_baro_p * 100));
|
||||
buffer.push(BitHelper.highByte(FC.POSITION_ESTIMATOR.w_z_baro_p * 100));
|
||||
|
||||
buffer.push(lowByte(FC.POSITION_ESTIMATOR.w_z_gps_p * 100));
|
||||
buffer.push(highByte(FC.POSITION_ESTIMATOR.w_z_gps_p * 100));
|
||||
buffer.push(BitHelper.lowByte(FC.POSITION_ESTIMATOR.w_z_gps_p * 100));
|
||||
buffer.push(BitHelper.highByte(FC.POSITION_ESTIMATOR.w_z_gps_p * 100));
|
||||
|
||||
buffer.push(lowByte(FC.POSITION_ESTIMATOR.w_z_gps_v * 100));
|
||||
buffer.push(highByte(FC.POSITION_ESTIMATOR.w_z_gps_v * 100));
|
||||
buffer.push(BitHelper.lowByte(FC.POSITION_ESTIMATOR.w_z_gps_v * 100));
|
||||
buffer.push(BitHelper.highByte(FC.POSITION_ESTIMATOR.w_z_gps_v * 100));
|
||||
|
||||
buffer.push(lowByte(FC.POSITION_ESTIMATOR.w_xy_gps_p * 100));
|
||||
buffer.push(highByte(FC.POSITION_ESTIMATOR.w_xy_gps_p * 100));
|
||||
buffer.push(BitHelper.lowByte(FC.POSITION_ESTIMATOR.w_xy_gps_p * 100));
|
||||
buffer.push(BitHelper.highByte(FC.POSITION_ESTIMATOR.w_xy_gps_p * 100));
|
||||
|
||||
buffer.push(lowByte(FC.POSITION_ESTIMATOR.w_xy_gps_v * 100));
|
||||
buffer.push(highByte(FC.POSITION_ESTIMATOR.w_xy_gps_v * 100));
|
||||
buffer.push(BitHelper.lowByte(FC.POSITION_ESTIMATOR.w_xy_gps_v * 100));
|
||||
buffer.push(BitHelper.highByte(FC.POSITION_ESTIMATOR.w_xy_gps_v * 100));
|
||||
|
||||
buffer.push(FC.POSITION_ESTIMATOR.gps_min_sats);
|
||||
buffer.push(FC.POSITION_ESTIMATOR.use_gps_velned);
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_SET_RTH_AND_LAND_CONFIG:
|
||||
buffer.push(lowByte(FC.RTH_AND_LAND_CONFIG.minRthDistance));
|
||||
buffer.push(highByte(FC.RTH_AND_LAND_CONFIG.minRthDistance));
|
||||
buffer.push(BitHelper.lowByte(FC.RTH_AND_LAND_CONFIG.minRthDistance));
|
||||
buffer.push(BitHelper.highByte(FC.RTH_AND_LAND_CONFIG.minRthDistance));
|
||||
|
||||
buffer.push(FC.RTH_AND_LAND_CONFIG.rthClimbFirst);
|
||||
buffer.push(FC.RTH_AND_LAND_CONFIG.rthClimbIgnoreEmergency);
|
||||
|
@ -2123,112 +2127,112 @@ var mspHelper = (function () {
|
|||
buffer.push(FC.RTH_AND_LAND_CONFIG.rthAllowLanding);
|
||||
buffer.push(FC.RTH_AND_LAND_CONFIG.rthAltControlMode);
|
||||
|
||||
buffer.push(lowByte(FC.RTH_AND_LAND_CONFIG.rthAbortThreshold));
|
||||
buffer.push(highByte(FC.RTH_AND_LAND_CONFIG.rthAbortThreshold));
|
||||
buffer.push(BitHelper.lowByte(FC.RTH_AND_LAND_CONFIG.rthAbortThreshold));
|
||||
buffer.push(BitHelper.highByte(FC.RTH_AND_LAND_CONFIG.rthAbortThreshold));
|
||||
|
||||
buffer.push(lowByte(FC.RTH_AND_LAND_CONFIG.rthAltitude));
|
||||
buffer.push(highByte(FC.RTH_AND_LAND_CONFIG.rthAltitude));
|
||||
buffer.push(BitHelper.lowByte(FC.RTH_AND_LAND_CONFIG.rthAltitude));
|
||||
buffer.push(BitHelper.highByte(FC.RTH_AND_LAND_CONFIG.rthAltitude));
|
||||
|
||||
buffer.push(lowByte(FC.RTH_AND_LAND_CONFIG.landMinAltVspd));
|
||||
buffer.push(highByte(FC.RTH_AND_LAND_CONFIG.landMinAltVspd));
|
||||
buffer.push(BitHelper.lowByte(FC.RTH_AND_LAND_CONFIG.landMinAltVspd));
|
||||
buffer.push(BitHelper.highByte(FC.RTH_AND_LAND_CONFIG.landMinAltVspd));
|
||||
|
||||
buffer.push(lowByte(FC.RTH_AND_LAND_CONFIG.landMaxAltVspd));
|
||||
buffer.push(highByte(FC.RTH_AND_LAND_CONFIG.landMaxAltVspd));
|
||||
buffer.push(BitHelper.lowByte(FC.RTH_AND_LAND_CONFIG.landMaxAltVspd));
|
||||
buffer.push(BitHelper.highByte(FC.RTH_AND_LAND_CONFIG.landMaxAltVspd));
|
||||
|
||||
buffer.push(lowByte(FC.RTH_AND_LAND_CONFIG.landSlowdownMinAlt));
|
||||
buffer.push(highByte(FC.RTH_AND_LAND_CONFIG.landSlowdownMinAlt));
|
||||
buffer.push(BitHelper.lowByte(FC.RTH_AND_LAND_CONFIG.landSlowdownMinAlt));
|
||||
buffer.push(BitHelper.highByte(FC.RTH_AND_LAND_CONFIG.landSlowdownMinAlt));
|
||||
|
||||
buffer.push(lowByte(FC.RTH_AND_LAND_CONFIG.landSlowdownMaxAlt));
|
||||
buffer.push(highByte(FC.RTH_AND_LAND_CONFIG.landSlowdownMaxAlt));
|
||||
buffer.push(BitHelper.lowByte(FC.RTH_AND_LAND_CONFIG.landSlowdownMaxAlt));
|
||||
buffer.push(BitHelper.highByte(FC.RTH_AND_LAND_CONFIG.landSlowdownMaxAlt));
|
||||
|
||||
buffer.push(lowByte(FC.RTH_AND_LAND_CONFIG.emergencyDescentRate));
|
||||
buffer.push(highByte(FC.RTH_AND_LAND_CONFIG.emergencyDescentRate));
|
||||
buffer.push(BitHelper.lowByte(FC.RTH_AND_LAND_CONFIG.emergencyDescentRate));
|
||||
buffer.push(BitHelper.highByte(FC.RTH_AND_LAND_CONFIG.emergencyDescentRate));
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_SET_FW_CONFIG:
|
||||
|
||||
buffer.push(lowByte(FC.FW_CONFIG.cruiseThrottle));
|
||||
buffer.push(highByte(FC.FW_CONFIG.cruiseThrottle));
|
||||
buffer.push(BitHelper.lowByte(FC.FW_CONFIG.cruiseThrottle));
|
||||
buffer.push(BitHelper.highByte(FC.FW_CONFIG.cruiseThrottle));
|
||||
|
||||
buffer.push(lowByte(FC.FW_CONFIG.minThrottle));
|
||||
buffer.push(highByte(FC.FW_CONFIG.minThrottle));
|
||||
buffer.push(BitHelper.lowByte(FC.FW_CONFIG.minThrottle));
|
||||
buffer.push(BitHelper.highByte(FC.FW_CONFIG.minThrottle));
|
||||
|
||||
buffer.push(lowByte(FC.FW_CONFIG.maxThrottle));
|
||||
buffer.push(highByte(FC.FW_CONFIG.maxThrottle));
|
||||
buffer.push(BitHelper.lowByte(FC.FW_CONFIG.maxThrottle));
|
||||
buffer.push(BitHelper.highByte(FC.FW_CONFIG.maxThrottle));
|
||||
|
||||
buffer.push(FC.FW_CONFIG.maxBankAngle);
|
||||
buffer.push(FC.FW_CONFIG.maxClimbAngle);
|
||||
buffer.push(FC.FW_CONFIG.maxDiveAngle);
|
||||
buffer.push(FC.FW_CONFIG.pitchToThrottle);
|
||||
|
||||
buffer.push(lowByte(FC.FW_CONFIG.loiterRadius));
|
||||
buffer.push(highByte(FC.FW_CONFIG.loiterRadius));
|
||||
buffer.push(BitHelper.lowByte(FC.FW_CONFIG.loiterRadius));
|
||||
buffer.push(BitHelper.highByte(FC.FW_CONFIG.loiterRadius));
|
||||
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_SET_FILTER_CONFIG:
|
||||
buffer.push(FC.FILTER_CONFIG.gyroSoftLpfHz);
|
||||
|
||||
buffer.push(lowByte(FC.FILTER_CONFIG.dtermLpfHz));
|
||||
buffer.push(highByte(FC.FILTER_CONFIG.dtermLpfHz));
|
||||
buffer.push(BitHelper.lowByte(FC.FILTER_CONFIG.dtermLpfHz));
|
||||
buffer.push(BitHelper.highByte(FC.FILTER_CONFIG.dtermLpfHz));
|
||||
|
||||
buffer.push(lowByte(FC.FILTER_CONFIG.yawLpfHz));
|
||||
buffer.push(highByte(FC.FILTER_CONFIG.yawLpfHz));
|
||||
buffer.push(BitHelper.lowByte(FC.FILTER_CONFIG.yawLpfHz));
|
||||
buffer.push(BitHelper.highByte(FC.FILTER_CONFIG.yawLpfHz));
|
||||
|
||||
buffer.push(lowByte(FC.FILTER_CONFIG.gyroNotchHz1));
|
||||
buffer.push(highByte(FC.FILTER_CONFIG.gyroNotchHz1));
|
||||
buffer.push(BitHelper.lowByte(FC.FILTER_CONFIG.gyroNotchHz1));
|
||||
buffer.push(BitHelper.highByte(FC.FILTER_CONFIG.gyroNotchHz1));
|
||||
|
||||
buffer.push(lowByte(FC.FILTER_CONFIG.gyroNotchCutoff1));
|
||||
buffer.push(highByte(FC.FILTER_CONFIG.gyroNotchCutoff1));
|
||||
buffer.push(BitHelper.lowByte(FC.FILTER_CONFIG.gyroNotchCutoff1));
|
||||
buffer.push(BitHelper.highByte(FC.FILTER_CONFIG.gyroNotchCutoff1));
|
||||
|
||||
buffer.push(lowByte(FC.FILTER_CONFIG.dtermNotchHz));
|
||||
buffer.push(highByte(FC.FILTER_CONFIG.dtermNotchHz));
|
||||
buffer.push(BitHelper.lowByte(FC.FILTER_CONFIG.dtermNotchHz));
|
||||
buffer.push(BitHelper.highByte(FC.FILTER_CONFIG.dtermNotchHz));
|
||||
|
||||
buffer.push(lowByte(FC.FILTER_CONFIG.dtermNotchCutoff));
|
||||
buffer.push(highByte(FC.FILTER_CONFIG.dtermNotchCutoff));
|
||||
buffer.push(BitHelper.lowByte(FC.FILTER_CONFIG.dtermNotchCutoff));
|
||||
buffer.push(BitHelper.highByte(FC.FILTER_CONFIG.dtermNotchCutoff));
|
||||
|
||||
buffer.push(lowByte(FC.FILTER_CONFIG.gyroNotchHz2));
|
||||
buffer.push(highByte(FC.FILTER_CONFIG.gyroNotchHz2));
|
||||
buffer.push(BitHelper.lowByte(FC.FILTER_CONFIG.gyroNotchHz2));
|
||||
buffer.push(BitHelper.highByte(FC.FILTER_CONFIG.gyroNotchHz2));
|
||||
|
||||
buffer.push(lowByte(FC.FILTER_CONFIG.gyroNotchCutoff2));
|
||||
buffer.push(highByte(FC.FILTER_CONFIG.gyroNotchCutoff2));
|
||||
buffer.push(BitHelper.lowByte(FC.FILTER_CONFIG.gyroNotchCutoff2));
|
||||
buffer.push(BitHelper.highByte(FC.FILTER_CONFIG.gyroNotchCutoff2));
|
||||
|
||||
buffer.push(lowByte(FC.FILTER_CONFIG.accNotchHz));
|
||||
buffer.push(highByte(FC.FILTER_CONFIG.accNotchHz));
|
||||
buffer.push(BitHelper.lowByte(FC.FILTER_CONFIG.accNotchHz));
|
||||
buffer.push(BitHelper.highByte(FC.FILTER_CONFIG.accNotchHz));
|
||||
|
||||
buffer.push(lowByte(FC.FILTER_CONFIG.accNotchCutoff));
|
||||
buffer.push(highByte(FC.FILTER_CONFIG.accNotchCutoff));
|
||||
buffer.push(BitHelper.lowByte(FC.FILTER_CONFIG.accNotchCutoff));
|
||||
buffer.push(BitHelper.highByte(FC.FILTER_CONFIG.accNotchCutoff));
|
||||
|
||||
buffer.push(lowByte(FC.FILTER_CONFIG.gyroStage2LowpassHz));
|
||||
buffer.push(highByte(FC.FILTER_CONFIG.gyroStage2LowpassHz));
|
||||
buffer.push(BitHelper.lowByte(FC.FILTER_CONFIG.gyroStage2LowpassHz));
|
||||
buffer.push(BitHelper.highByte(FC.FILTER_CONFIG.gyroStage2LowpassHz));
|
||||
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_SET_PID_ADVANCED:
|
||||
buffer.push(lowByte(FC.PID_ADVANCED.rollPitchItermIgnoreRate));
|
||||
buffer.push(highByte(FC.PID_ADVANCED.rollPitchItermIgnoreRate));
|
||||
buffer.push(BitHelper.lowByte(FC.PID_ADVANCED.rollPitchItermIgnoreRate));
|
||||
buffer.push(BitHelper.highByte(FC.PID_ADVANCED.rollPitchItermIgnoreRate));
|
||||
|
||||
buffer.push(lowByte(FC.PID_ADVANCED.yawItermIgnoreRate));
|
||||
buffer.push(highByte(FC.PID_ADVANCED.yawItermIgnoreRate));
|
||||
buffer.push(BitHelper.lowByte(FC.PID_ADVANCED.yawItermIgnoreRate));
|
||||
buffer.push(BitHelper.highByte(FC.PID_ADVANCED.yawItermIgnoreRate));
|
||||
|
||||
buffer.push(lowByte(FC.PID_ADVANCED.yawPLimit));
|
||||
buffer.push(highByte(FC.PID_ADVANCED.yawPLimit));
|
||||
buffer.push(BitHelper.lowByte(FC.PID_ADVANCED.yawPLimit));
|
||||
buffer.push(BitHelper.highByte(FC.PID_ADVANCED.yawPLimit));
|
||||
|
||||
buffer.push(0); //BF: currentProfile->pidProfile.deltaMethod
|
||||
buffer.push(0); //BF: currentProfile->pidProfile.vbatPidCompensation
|
||||
buffer.push(0); //BF: currentProfile->pidProfile.setpointRelaxRatio
|
||||
|
||||
buffer.push(FC.PID_ADVANCED.dtermSetpointWeight);
|
||||
buffer.push(lowByte(FC.PID_ADVANCED.pidSumLimit));
|
||||
buffer.push(highByte(FC.PID_ADVANCED.pidSumLimit));
|
||||
buffer.push(BitHelper.lowByte(FC.PID_ADVANCED.pidSumLimit));
|
||||
buffer.push(BitHelper.highByte(FC.PID_ADVANCED.pidSumLimit));
|
||||
|
||||
buffer.push(0); //BF: currentProfile->pidProfile.itermThrottleGain
|
||||
|
||||
buffer.push(lowByte(FC.PID_ADVANCED.axisAccelerationLimitRollPitch));
|
||||
buffer.push(highByte(FC.PID_ADVANCED.axisAccelerationLimitRollPitch));
|
||||
buffer.push(BitHelper.lowByte(FC.PID_ADVANCED.axisAccelerationLimitRollPitch));
|
||||
buffer.push(BitHelper.highByte(FC.PID_ADVANCED.axisAccelerationLimitRollPitch));
|
||||
|
||||
buffer.push(lowByte(FC.PID_ADVANCED.axisAccelerationLimitYaw));
|
||||
buffer.push(highByte(FC.PID_ADVANCED.axisAccelerationLimitYaw));
|
||||
buffer.push(BitHelper.lowByte(FC.PID_ADVANCED.axisAccelerationLimitYaw));
|
||||
buffer.push(BitHelper.highByte(FC.PID_ADVANCED.axisAccelerationLimitYaw));
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP_SET_SENSOR_CONFIG:
|
||||
|
@ -2255,28 +2259,28 @@ var mspHelper = (function () {
|
|||
buffer.push(FC.MIXER_CONFIG.motorStopOnLow);
|
||||
buffer.push(FC.MIXER_CONFIG.platformType);
|
||||
buffer.push(FC.MIXER_CONFIG.hasFlaps);
|
||||
buffer.push(lowByte(FC.MIXER_CONFIG.appliedMixerPreset));
|
||||
buffer.push(highByte(FC.MIXER_CONFIG.appliedMixerPreset));
|
||||
buffer.push(BitHelper.lowByte(FC.MIXER_CONFIG.appliedMixerPreset));
|
||||
buffer.push(BitHelper.highByte(FC.MIXER_CONFIG.appliedMixerPreset));
|
||||
buffer.push(0); //Filler byte to match expect payload length
|
||||
buffer.push(0); //Filler byte to match expect payload length
|
||||
break;
|
||||
|
||||
case MSPCodes.MSP2_INAV_SET_MC_BRAKING:
|
||||
buffer.push(lowByte(FC.BRAKING_CONFIG.speedThreshold));
|
||||
buffer.push(highByte(FC.BRAKING_CONFIG.speedThreshold));
|
||||
buffer.push(lowByte(FC.BRAKING_CONFIG.disengageSpeed));
|
||||
buffer.push(highByte(FC.BRAKING_CONFIG.disengageSpeed));
|
||||
buffer.push(lowByte(FC.BRAKING_CONFIG.timeout));
|
||||
buffer.push(highByte(FC.BRAKING_CONFIG.timeout));
|
||||
buffer.push(BitHelper.lowByte(FC.BRAKING_CONFIG.speedThreshold));
|
||||
buffer.push(BitHelper.highByte(FC.BRAKING_CONFIG.speedThreshold));
|
||||
buffer.push(BitHelper.lowByte(FC.BRAKING_CONFIG.disengageSpeed));
|
||||
buffer.push(BitHelper.highByte(FC.BRAKING_CONFIG.disengageSpeed));
|
||||
buffer.push(BitHelper.lowByte(FC.BRAKING_CONFIG.timeout));
|
||||
buffer.push(BitHelper.highByte(FC.BRAKING_CONFIG.timeout));
|
||||
|
||||
buffer.push(FC.BRAKING_CONFIG.boostFactor);
|
||||
|
||||
buffer.push(lowByte(FC.BRAKING_CONFIG.boostTimeout));
|
||||
buffer.push(highByte(FC.BRAKING_CONFIG.boostTimeout));
|
||||
buffer.push(lowByte(FC.BRAKING_CONFIG.boostSpeedThreshold));
|
||||
buffer.push(highByte(FC.BRAKING_CONFIG.boostSpeedThreshold));
|
||||
buffer.push(lowByte(FC.BRAKING_CONFIG.boostDisengageSpeed));
|
||||
buffer.push(highByte(FC.BRAKING_CONFIG.boostDisengageSpeed));
|
||||
buffer.push(BitHelper.lowByte(FC.BRAKING_CONFIG.boostTimeout));
|
||||
buffer.push(BitHelper.highByte(FC.BRAKING_CONFIG.boostTimeout));
|
||||
buffer.push(BitHelper.lowByte(FC.BRAKING_CONFIG.boostSpeedThreshold));
|
||||
buffer.push(BitHelper.highByte(FC.BRAKING_CONFIG.boostSpeedThreshold));
|
||||
buffer.push(BitHelper.lowByte(FC.BRAKING_CONFIG.boostDisengageSpeed));
|
||||
buffer.push(BitHelper.highByte(FC.BRAKING_CONFIG.boostDisengageSpeed));
|
||||
|
||||
buffer.push(FC.BRAKING_CONFIG.bankAngle);
|
||||
break;
|
||||
|
@ -2293,8 +2297,8 @@ var mspHelper = (function () {
|
|||
case MSPCodes.MSP2_INAV_EZ_TUNE_SET:
|
||||
|
||||
buffer.push(FC.EZ_TUNE.enabled);
|
||||
buffer.push(lowByte(FC.EZ_TUNE.filterHz));
|
||||
buffer.push(highByte(FC.EZ_TUNE.filterHz));
|
||||
buffer.push(BitHelper.lowByte(FC.EZ_TUNE.filterHz));
|
||||
buffer.push(BitHelper.highByte(FC.EZ_TUNE.filterHz));
|
||||
buffer.push(FC.EZ_TUNE.axisRatio);
|
||||
buffer.push(FC.EZ_TUNE.response);
|
||||
buffer.push(FC.EZ_TUNE.damping);
|
||||
|
@ -2322,8 +2326,8 @@ var mspHelper = (function () {
|
|||
var buffer = [];
|
||||
|
||||
for (var i = 0; i < channels.length; i++) {
|
||||
buffer.push(specificByte(channels[i], 0));
|
||||
buffer.push(specificByte(channels[i], 1));
|
||||
buffer.push(BitHelper.specificByte(channels[i], 0));
|
||||
buffer.push(BitHelper.specificByte(channels[i], 1));
|
||||
}
|
||||
|
||||
MSP.send_message(MSPCodes.MSP_SET_RAW_RC, buffer, false);
|
||||
|
@ -2334,10 +2338,10 @@ var mspHelper = (function () {
|
|||
var messageId = MSPCodes.MSP_SET_BLACKBOX_CONFIG;
|
||||
buffer.push(FC.BLACKBOX.blackboxDevice & 0xFF);
|
||||
messageId = MSPCodes.MSP2_SET_BLACKBOX_CONFIG;
|
||||
buffer.push(lowByte(FC.BLACKBOX.blackboxRateNum));
|
||||
buffer.push(highByte(FC.BLACKBOX.blackboxRateNum));
|
||||
buffer.push(lowByte(FC.BLACKBOX.blackboxRateDenom));
|
||||
buffer.push(highByte(FC.BLACKBOX.blackboxRateDenom));
|
||||
buffer.push(BitHelper.lowByte(FC.BLACKBOX.blackboxRateNum));
|
||||
buffer.push(BitHelper.highByte(FC.BLACKBOX.blackboxRateNum));
|
||||
buffer.push(BitHelper.lowByte(FC.BLACKBOX.blackboxRateDenom));
|
||||
buffer.push(BitHelper.highByte(FC.BLACKBOX.blackboxRateDenom));
|
||||
buffer.push32(FC.BLACKBOX.blackboxIncludeFlags);
|
||||
//noinspection JSUnusedLocalSymbols
|
||||
MSP.send_message(messageId, buffer, false, function (response) {
|
||||
|
@ -2366,16 +2370,16 @@ var mspHelper = (function () {
|
|||
|
||||
buffer.push(servoIndex);
|
||||
|
||||
buffer.push(lowByte(servoConfiguration.min));
|
||||
buffer.push(highByte(servoConfiguration.min));
|
||||
buffer.push(BitHelper.lowByte(servoConfiguration.min));
|
||||
buffer.push(BitHelper.highByte(servoConfiguration.min));
|
||||
|
||||
buffer.push(lowByte(servoConfiguration.max));
|
||||
buffer.push(highByte(servoConfiguration.max));
|
||||
buffer.push(BitHelper.lowByte(servoConfiguration.max));
|
||||
buffer.push(BitHelper.highByte(servoConfiguration.max));
|
||||
|
||||
buffer.push(lowByte(servoConfiguration.middle));
|
||||
buffer.push(highByte(servoConfiguration.middle));
|
||||
buffer.push(BitHelper.lowByte(servoConfiguration.middle));
|
||||
buffer.push(BitHelper.highByte(servoConfiguration.middle));
|
||||
|
||||
buffer.push(lowByte(servoConfiguration.rate));
|
||||
buffer.push(BitHelper.lowByte(servoConfiguration.rate));
|
||||
|
||||
buffer.push(0);
|
||||
buffer.push(0);
|
||||
|
@ -2423,8 +2427,8 @@ var mspHelper = (function () {
|
|||
buffer.push(servoIndex);
|
||||
buffer.push(servoRule.getTarget());
|
||||
buffer.push(servoRule.getInput());
|
||||
buffer.push(lowByte(servoRule.getRate()));
|
||||
buffer.push(highByte(servoRule.getRate()));
|
||||
buffer.push(BitHelper.lowByte(servoRule.getRate()));
|
||||
buffer.push(BitHelper.highByte(servoRule.getRate()));
|
||||
buffer.push(servoRule.getSpeed());
|
||||
buffer.push(servoRule.getConditionId());
|
||||
|
||||
|
@ -2460,17 +2464,17 @@ var mspHelper = (function () {
|
|||
|
||||
buffer.push(servoIndex);
|
||||
|
||||
buffer.push(lowByte(rule.getThrottleForMsp()));
|
||||
buffer.push(highByte(rule.getThrottleForMsp()));
|
||||
buffer.push(BitHelper.lowByte(rule.getThrottleForMsp()));
|
||||
buffer.push(BitHelper.highByte(rule.getThrottleForMsp()));
|
||||
|
||||
buffer.push(lowByte(rule.getRollForMsp()));
|
||||
buffer.push(highByte(rule.getRollForMsp()));
|
||||
buffer.push(BitHelper.lowByte(rule.getRollForMsp()));
|
||||
buffer.push(BitHelper.highByte(rule.getRollForMsp()));
|
||||
|
||||
buffer.push(lowByte(rule.getPitchForMsp()));
|
||||
buffer.push(highByte(rule.getPitchForMsp()));
|
||||
buffer.push(BitHelper.lowByte(rule.getPitchForMsp()));
|
||||
buffer.push(BitHelper.highByte(rule.getPitchForMsp()));
|
||||
|
||||
buffer.push(lowByte(rule.getYawForMsp()));
|
||||
buffer.push(highByte(rule.getYawForMsp()));
|
||||
buffer.push(BitHelper.lowByte(rule.getYawForMsp()));
|
||||
buffer.push(BitHelper.highByte(rule.getYawForMsp()));
|
||||
|
||||
// prepare for next iteration
|
||||
servoIndex++;
|
||||
|
@ -2526,15 +2530,15 @@ var mspHelper = (function () {
|
|||
buffer.push(condition.getActivatorId());
|
||||
buffer.push(condition.getOperation());
|
||||
buffer.push(condition.getOperandAType());
|
||||
buffer.push(specificByte(condition.getOperandAValue(), 0));
|
||||
buffer.push(specificByte(condition.getOperandAValue(), 1));
|
||||
buffer.push(specificByte(condition.getOperandAValue(), 2));
|
||||
buffer.push(specificByte(condition.getOperandAValue(), 3));
|
||||
buffer.push(BitHelper.specificByte(condition.getOperandAValue(), 0));
|
||||
buffer.push(BitHelper.specificByte(condition.getOperandAValue(), 1));
|
||||
buffer.push(BitHelper.specificByte(condition.getOperandAValue(), 2));
|
||||
buffer.push(BitHelper.specificByte(condition.getOperandAValue(), 3));
|
||||
buffer.push(condition.getOperandBType());
|
||||
buffer.push(specificByte(condition.getOperandBValue(), 0));
|
||||
buffer.push(specificByte(condition.getOperandBValue(), 1));
|
||||
buffer.push(specificByte(condition.getOperandBValue(), 2));
|
||||
buffer.push(specificByte(condition.getOperandBValue(), 3));
|
||||
buffer.push(BitHelper.specificByte(condition.getOperandBValue(), 0));
|
||||
buffer.push(BitHelper.specificByte(condition.getOperandBValue(), 1));
|
||||
buffer.push(BitHelper.specificByte(condition.getOperandBValue(), 2));
|
||||
buffer.push(BitHelper.specificByte(condition.getOperandBValue(), 3));
|
||||
buffer.push(condition.getFlags());
|
||||
|
||||
// prepare for next iteration
|
||||
|
@ -2571,23 +2575,23 @@ var mspHelper = (function () {
|
|||
buffer.push(pidIndex);
|
||||
buffer.push(pid.getEnabled());
|
||||
buffer.push(pid.getSetpointType());
|
||||
buffer.push(specificByte(pid.getSetpointValue(), 0));
|
||||
buffer.push(specificByte(pid.getSetpointValue(), 1));
|
||||
buffer.push(specificByte(pid.getSetpointValue(), 2));
|
||||
buffer.push(specificByte(pid.getSetpointValue(), 3));
|
||||
buffer.push(BitHelper.specificByte(pid.getSetpointValue(), 0));
|
||||
buffer.push(BitHelper.specificByte(pid.getSetpointValue(), 1));
|
||||
buffer.push(BitHelper.specificByte(pid.getSetpointValue(), 2));
|
||||
buffer.push(BitHelper.specificByte(pid.getSetpointValue(), 3));
|
||||
buffer.push(pid.getMeasurementType());
|
||||
buffer.push(specificByte(pid.getMeasurementValue(), 0));
|
||||
buffer.push(specificByte(pid.getMeasurementValue(), 1));
|
||||
buffer.push(specificByte(pid.getMeasurementValue(), 2));
|
||||
buffer.push(specificByte(pid.getMeasurementValue(), 3));
|
||||
buffer.push(specificByte(pid.getGainP(), 0));
|
||||
buffer.push(specificByte(pid.getGainP(), 1));
|
||||
buffer.push(specificByte(pid.getGainI(), 0));
|
||||
buffer.push(specificByte(pid.getGainI(), 1));
|
||||
buffer.push(specificByte(pid.getGainD(), 0));
|
||||
buffer.push(specificByte(pid.getGainD(), 1));
|
||||
buffer.push(specificByte(pid.getGainFF(), 0));
|
||||
buffer.push(specificByte(pid.getGainFF(), 1));
|
||||
buffer.push(BitHelper.specificByte(pid.getMeasurementValue(), 0));
|
||||
buffer.push(BitHelper.specificByte(pid.getMeasurementValue(), 1));
|
||||
buffer.push(BitHelper.specificByte(pid.getMeasurementValue(), 2));
|
||||
buffer.push(BitHelper.specificByte(pid.getMeasurementValue(), 3));
|
||||
buffer.push(BitHelper.specificByte(pid.getGainP(), 0));
|
||||
buffer.push(BitHelper.specificByte(pid.getGainP(), 1));
|
||||
buffer.push(BitHelper.specificByte(pid.getGainI(), 0));
|
||||
buffer.push(BitHelper.specificByte(pid.getGainI(), 1));
|
||||
buffer.push(BitHelper.specificByte(pid.getGainD(), 0));
|
||||
buffer.push(BitHelper.specificByte(pid.getGainD(), 1));
|
||||
buffer.push(BitHelper.specificByte(pid.getGainFF(), 0));
|
||||
buffer.push(BitHelper.specificByte(pid.getGainFF(), 1));
|
||||
|
||||
// prepare for next iteration
|
||||
pidIndex++;
|
||||
|
@ -2643,8 +2647,8 @@ var mspHelper = (function () {
|
|||
|
||||
// For API > 2.0.0 we support requesting payload size - request 4KiB and let firmware decide what actual size to send
|
||||
if (FC.CONFIG.apiVersion && semver.gte(FC.CONFIG.apiVersion, "2.0.0")) {
|
||||
buffer.push(lowByte(4096));
|
||||
buffer.push(highByte(4096));
|
||||
buffer.push(BitHelper.lowByte(4096));
|
||||
buffer.push(BitHelper.highByte(4096));
|
||||
}
|
||||
|
||||
MSP.send_message(MSPCodes.MSP_DATAFLASH_READ, buffer, false, function (response) {
|
||||
|
@ -2681,8 +2685,8 @@ var mspHelper = (function () {
|
|||
var buffer = [];
|
||||
buffer.push(rxFailIndex);
|
||||
buffer.push(rxFail.mode);
|
||||
buffer.push(lowByte(rxFail.value));
|
||||
buffer.push(highByte(rxFail.value));
|
||||
buffer.push(BitHelper.lowByte(rxFail.value));
|
||||
buffer.push(BitHelper.highByte(rxFail.value));
|
||||
|
||||
// prepare for next iteration
|
||||
rxFailIndex++;
|
||||
|
@ -2772,8 +2776,8 @@ var mspHelper = (function () {
|
|||
for (var colorIndex = 0; colorIndex < FC.LED_COLORS.length; colorIndex++) {
|
||||
var color = FC.LED_COLORS[colorIndex];
|
||||
|
||||
buffer.push(specificByte(color.h, 0));
|
||||
buffer.push(specificByte(color.h, 1));
|
||||
buffer.push(BitHelper.specificByte(color.h, 0));
|
||||
buffer.push(BitHelper.specificByte(color.h, 1));
|
||||
buffer.push(color.s);
|
||||
buffer.push(color.v);
|
||||
}
|
||||
|
@ -2857,11 +2861,11 @@ var mspHelper = (function () {
|
|||
|
||||
extra |= (0 << 2); // parameters
|
||||
|
||||
buffer.push(specificByte(mask, 0));
|
||||
buffer.push(specificByte(mask, 1));
|
||||
buffer.push(specificByte(mask, 2));
|
||||
buffer.push(specificByte(mask, 3));
|
||||
buffer.push(specificByte(extra, 0));
|
||||
buffer.push(BitHelper.specificByte(mask, 0));
|
||||
buffer.push(BitHelper.specificByte(mask, 1));
|
||||
buffer.push(BitHelper.specificByte(mask, 2));
|
||||
buffer.push(BitHelper.specificByte(mask, 3));
|
||||
buffer.push(BitHelper.specificByte(extra, 0));
|
||||
|
||||
// prepare for next iteration
|
||||
ledIndex++;
|
||||
|
|
|
@ -23,6 +23,8 @@ const defaultsDialog = require('./defaults_dialog');
|
|||
const { SITLProcess } = require('./sitl');
|
||||
const update = require('./globalUpdates.js');
|
||||
const BitHelper = require('./bitHelper.js');
|
||||
const BOARD = require('./boards.js')
|
||||
const jBox = require('./libraries/jBox/jBox.min.js')
|
||||
|
||||
var SerialBackend = (function () {
|
||||
|
||||
|
@ -147,7 +149,7 @@ var SerialBackend = (function () {
|
|||
GUI.updateManualPortVisibility();
|
||||
|
||||
publicScope.$portOverride.on('change', function () {
|
||||
store.set('portOverride', privateScope.$portOverride.val());
|
||||
store.set('portOverride', publicScope.$portOverride.val());
|
||||
});
|
||||
|
||||
publicScope.$portOverride.val(store.get('portOverride', ''));
|
||||
|
@ -480,7 +482,7 @@ var SerialBackend = (function () {
|
|||
$('#dataflash_wrapper_global').hide();
|
||||
$('#quad-status_wrapper').hide();
|
||||
|
||||
updateFirmwareVersion();
|
||||
//updateFirmwareVersion();
|
||||
}
|
||||
|
||||
publicScope.read_serial = function (info) {
|
||||
|
|
|
@ -1,5 +1,12 @@
|
|||
'use strict';
|
||||
|
||||
const mapSeries = require('promise-map-series')
|
||||
|
||||
const mspHelper = require('./../js/msp/MSPHelper');
|
||||
const { GUI } = require('./gui');
|
||||
const FC = require('./fc');
|
||||
const { globalSettings, UnitType } = require('./globalSettings');
|
||||
|
||||
function padZeros(val, length) {
|
||||
let str = val.toString();
|
||||
|
||||
|
@ -638,3 +645,5 @@ var Settings = (function () {
|
|||
|
||||
return self;
|
||||
})();
|
||||
|
||||
module.exports = Settings;
|
||||
|
|
272
package-lock.json
generated
272
package-lock.json
generated
|
@ -42,9 +42,9 @@
|
|||
}
|
||||
},
|
||||
"node_modules/@babel/runtime": {
|
||||
"version": "7.23.9",
|
||||
"resolved": "https://registry.npmjs.org/@babel/runtime/-/runtime-7.23.9.tgz",
|
||||
"integrity": "sha512-0CX6F+BI2s9dkUqr08KFrAIZgNFj75rdBU/DjCyYLIaV/quFjkk6T+EJ2LkZHyZTbEV4L5p97mNkUsHl2wLFAw==",
|
||||
"version": "7.24.1",
|
||||
"resolved": "https://registry.npmjs.org/@babel/runtime/-/runtime-7.24.1.tgz",
|
||||
"integrity": "sha512-+BIznRzyqBf+2wCTxcKE3wDjfGeCoVE61KSHGpkzqrLi8qxqFwBeUFyId2cxkTmm55fzDGnm0+yCxaxygrLUnQ==",
|
||||
"dependencies": {
|
||||
"regenerator-runtime": "^0.14.0"
|
||||
},
|
||||
|
@ -53,9 +53,9 @@
|
|||
}
|
||||
},
|
||||
"node_modules/@electron-forge/cli": {
|
||||
"version": "7.3.0",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/cli/-/cli-7.3.0.tgz",
|
||||
"integrity": "sha512-tIzNYTvCEjJbma7zLWpa03phLKX/pd9f+vG+0HlIpmESMFGWhyLDzunZn0YOOXPRKpCTVg5RpC+BVte1Da4VjQ==",
|
||||
"version": "7.3.1",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/cli/-/cli-7.3.1.tgz",
|
||||
"integrity": "sha512-qPIeLxUO5d0xqiJZn0eZ17ytkDjFCN1acgrO/4B767PHsy5MmylyK0ulnRje/aQ/K+u/bN7N0cDyWs3JAEYZrQ==",
|
||||
"dev": true,
|
||||
"funding": [
|
||||
{
|
||||
|
@ -68,8 +68,8 @@
|
|||
}
|
||||
],
|
||||
"dependencies": {
|
||||
"@electron-forge/core": "7.3.0",
|
||||
"@electron-forge/shared-types": "7.3.0",
|
||||
"@electron-forge/core": "7.3.1",
|
||||
"@electron-forge/shared-types": "7.3.1",
|
||||
"@electron/get": "^3.0.0",
|
||||
"chalk": "^4.0.0",
|
||||
"commander": "^4.1.1",
|
||||
|
@ -88,9 +88,9 @@
|
|||
}
|
||||
},
|
||||
"node_modules/@electron-forge/core": {
|
||||
"version": "7.3.0",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/core/-/core-7.3.0.tgz",
|
||||
"integrity": "sha512-Z0wvs/YutUzo5xbCBjhoWSnlO1y5DbM4LMa5Di4Dxaf8v/xi7PQ/ncjAiOJKFYI8mG23Nn8Ae13weG0tiXISbA==",
|
||||
"version": "7.3.1",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/core/-/core-7.3.1.tgz",
|
||||
"integrity": "sha512-Gveci4eAIk4zH/cS+reHqccoAN/qJPde9K/5TotNyNvu8l6QxGd+qJL4bqCixUUXdQ7Nq4tEG12gB/DtUHb6Bw==",
|
||||
"dev": true,
|
||||
"funding": [
|
||||
{
|
||||
|
@ -103,19 +103,19 @@
|
|||
}
|
||||
],
|
||||
"dependencies": {
|
||||
"@electron-forge/core-utils": "7.3.0",
|
||||
"@electron-forge/maker-base": "7.3.0",
|
||||
"@electron-forge/plugin-base": "7.3.0",
|
||||
"@electron-forge/publisher-base": "7.3.0",
|
||||
"@electron-forge/shared-types": "7.3.0",
|
||||
"@electron-forge/template-base": "7.3.0",
|
||||
"@electron-forge/template-vite": "7.3.0",
|
||||
"@electron-forge/template-vite-typescript": "7.3.0",
|
||||
"@electron-forge/template-webpack": "7.3.0",
|
||||
"@electron-forge/template-webpack-typescript": "7.3.0",
|
||||
"@electron-forge/tracer": "7.3.0",
|
||||
"@electron-forge/core-utils": "7.3.1",
|
||||
"@electron-forge/maker-base": "7.3.1",
|
||||
"@electron-forge/plugin-base": "7.3.1",
|
||||
"@electron-forge/publisher-base": "7.3.1",
|
||||
"@electron-forge/shared-types": "7.3.1",
|
||||
"@electron-forge/template-base": "7.3.1",
|
||||
"@electron-forge/template-vite": "7.3.1",
|
||||
"@electron-forge/template-vite-typescript": "7.3.1",
|
||||
"@electron-forge/template-webpack": "7.3.1",
|
||||
"@electron-forge/template-webpack-typescript": "7.3.1",
|
||||
"@electron-forge/tracer": "7.3.1",
|
||||
"@electron/get": "^3.0.0",
|
||||
"@electron/packager": "^18.1.2",
|
||||
"@electron/packager": "^18.1.3",
|
||||
"@electron/rebuild": "^3.2.10",
|
||||
"@malept/cross-spawn-promise": "^2.0.0",
|
||||
"chalk": "^4.0.0",
|
||||
|
@ -144,12 +144,12 @@
|
|||
}
|
||||
},
|
||||
"node_modules/@electron-forge/core-utils": {
|
||||
"version": "7.3.0",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/core-utils/-/core-utils-7.3.0.tgz",
|
||||
"integrity": "sha512-cKeWuC8zYcp2n9caRWvCQgwIFtDqaUlwQVeg2VBpgJTGYHNKEDQHadR2xtIXTcfNgPUbQEAXiaS2xuxuhPQLfw==",
|
||||
"version": "7.3.1",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/core-utils/-/core-utils-7.3.1.tgz",
|
||||
"integrity": "sha512-+DLk6Futxb4576vi5FKjem1v9+D8EuaLVQy9Y3om7oYkc5JC3eTVSqbryVTEfoyNIm1xdZqya4tRSQ9v7EWu7A==",
|
||||
"dev": true,
|
||||
"dependencies": {
|
||||
"@electron-forge/shared-types": "7.3.0",
|
||||
"@electron-forge/shared-types": "7.3.1",
|
||||
"@electron/rebuild": "^3.2.10",
|
||||
"@malept/cross-spawn-promise": "^2.0.0",
|
||||
"chalk": "^4.0.0",
|
||||
|
@ -165,12 +165,12 @@
|
|||
}
|
||||
},
|
||||
"node_modules/@electron-forge/maker-base": {
|
||||
"version": "7.3.0",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/maker-base/-/maker-base-7.3.0.tgz",
|
||||
"integrity": "sha512-1o0YT1QBCf9oAfQNJmWQehn+DQp8mqaUbwaivNtIgTKRlzAVfD7UoAS7izuUqEW6M6NOvFXfCQjp7IgGckVVBg==",
|
||||
"version": "7.3.1",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/maker-base/-/maker-base-7.3.1.tgz",
|
||||
"integrity": "sha512-FWQg2IIBodLh6ms6UvIRdQ4WiNUrUvlzUfIyKQ/DbMk9MUCxbzqY8YI76Uv5vna/rGdXf0lPOC48tpOgTREv/g==",
|
||||
"dev": true,
|
||||
"dependencies": {
|
||||
"@electron-forge/shared-types": "7.3.0",
|
||||
"@electron-forge/shared-types": "7.3.1",
|
||||
"fs-extra": "^10.0.0",
|
||||
"which": "^2.0.2"
|
||||
},
|
||||
|
@ -179,13 +179,13 @@
|
|||
}
|
||||
},
|
||||
"node_modules/@electron-forge/maker-deb": {
|
||||
"version": "7.3.0",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/maker-deb/-/maker-deb-7.3.0.tgz",
|
||||
"integrity": "sha512-rlTYjF18p1rVVzInr9kJPSwELvu2ycLp7qGi/Nrj91N2cS92D3z8l6UkQE6wvhsBMhhL0sOX+NyDhvzKoRsWNQ==",
|
||||
"version": "7.3.1",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/maker-deb/-/maker-deb-7.3.1.tgz",
|
||||
"integrity": "sha512-A+UAxIcSsUoks9hiYoYHe3GIz02OkBBY7quVfiSUrYe2HXB7/++PsxOJ6pSwAFyJ9gzRBU+rSigocXOCFyvB8Q==",
|
||||
"dev": true,
|
||||
"dependencies": {
|
||||
"@electron-forge/maker-base": "7.3.0",
|
||||
"@electron-forge/shared-types": "7.3.0"
|
||||
"@electron-forge/maker-base": "7.3.1",
|
||||
"@electron-forge/shared-types": "7.3.1"
|
||||
},
|
||||
"engines": {
|
||||
"node": ">= 16.4.0"
|
||||
|
@ -195,13 +195,13 @@
|
|||
}
|
||||
},
|
||||
"node_modules/@electron-forge/maker-rpm": {
|
||||
"version": "7.3.0",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/maker-rpm/-/maker-rpm-7.3.0.tgz",
|
||||
"integrity": "sha512-EzfkRcnWeLYHUvGmtP2KcGU8I93izAaGfYze1xQqG6BQ0FXjEm7xcESy2gZThX/2vEtQUdjCdIbfVf4yveZKFQ==",
|
||||
"version": "7.3.1",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/maker-rpm/-/maker-rpm-7.3.1.tgz",
|
||||
"integrity": "sha512-ICf9SyXoT6nNC8qROIJhuiWByDhgtf0CWVUKIC8oDvQ2N3hQCNhDwpKycAm2psX30j1M/HpKfqe0C+pBntcW+w==",
|
||||
"dev": true,
|
||||
"dependencies": {
|
||||
"@electron-forge/maker-base": "7.3.0",
|
||||
"@electron-forge/shared-types": "7.3.0"
|
||||
"@electron-forge/maker-base": "7.3.1",
|
||||
"@electron-forge/shared-types": "7.3.1"
|
||||
},
|
||||
"engines": {
|
||||
"node": ">= 16.4.0"
|
||||
|
@ -211,30 +211,30 @@
|
|||
}
|
||||
},
|
||||
"node_modules/@electron-forge/maker-squirrel": {
|
||||
"version": "7.3.0",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/maker-squirrel/-/maker-squirrel-7.3.0.tgz",
|
||||
"integrity": "sha512-JXKKwztnIDiMjzwUwROphZyIAtUivw7YOsWhskuxj/KhxtHpksNboBbwhvbvX8stfzVl2M95IgqATyPJXClQ9w==",
|
||||
"version": "7.3.1",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/maker-squirrel/-/maker-squirrel-7.3.1.tgz",
|
||||
"integrity": "sha512-eUOTdt5KTt/kWl1HIQHBOvlJbrhqVeXMiPwSXffVWWWJb+h+ckFdQmu1jtQySWKcgj7ZkbP1j+0uQFm82Nb5gQ==",
|
||||
"dev": true,
|
||||
"dependencies": {
|
||||
"@electron-forge/maker-base": "7.3.0",
|
||||
"@electron-forge/shared-types": "7.3.0",
|
||||
"@electron-forge/maker-base": "7.3.1",
|
||||
"@electron-forge/shared-types": "7.3.1",
|
||||
"fs-extra": "^10.0.0"
|
||||
},
|
||||
"engines": {
|
||||
"node": ">= 16.4.0"
|
||||
},
|
||||
"optionalDependencies": {
|
||||
"electron-winstaller": "^5.0.0"
|
||||
"electron-winstaller": "^5.3.0"
|
||||
}
|
||||
},
|
||||
"node_modules/@electron-forge/maker-zip": {
|
||||
"version": "7.3.0",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/maker-zip/-/maker-zip-7.3.0.tgz",
|
||||
"integrity": "sha512-VYYLScDpibVIiMRK7JWeCS9G8VYvPXa1X6p6fNYQoFOWommG9zC7OOnFfNnLBrH1+0ginZRJeLD1zo+cM12JuQ==",
|
||||
"version": "7.3.1",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/maker-zip/-/maker-zip-7.3.1.tgz",
|
||||
"integrity": "sha512-kH8M5gZnzO13rZIjzEPe+xLFZ0OrxLpJCrF64km2SksVCP8GKdWuD92z/vXZsyXfzQpa8mjHvqigzAB5R6mEiQ==",
|
||||
"dev": true,
|
||||
"dependencies": {
|
||||
"@electron-forge/maker-base": "7.3.0",
|
||||
"@electron-forge/shared-types": "7.3.0",
|
||||
"@electron-forge/maker-base": "7.3.1",
|
||||
"@electron-forge/shared-types": "7.3.1",
|
||||
"cross-zip": "^4.0.0",
|
||||
"fs-extra": "^10.0.0",
|
||||
"got": "^11.8.5"
|
||||
|
@ -244,37 +244,37 @@
|
|||
}
|
||||
},
|
||||
"node_modules/@electron-forge/plugin-base": {
|
||||
"version": "7.3.0",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/plugin-base/-/plugin-base-7.3.0.tgz",
|
||||
"integrity": "sha512-cS0dqi9yTMgKzy1RhJ21YheRjWSbUh0bOKuByYAWevdqMZfqO2KyhXIsmH5QizL+bub8uWOUsknXVrOp73NLfw==",
|
||||
"version": "7.3.1",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/plugin-base/-/plugin-base-7.3.1.tgz",
|
||||
"integrity": "sha512-4mAzUqfOkRqBwFmE3yO+9dEM2nK9PN/UXFALjN42GS7hbLorluHVmzELkC48Y6M0k1Q+GN3NAdzfMiD+X2PWVA==",
|
||||
"dev": true,
|
||||
"dependencies": {
|
||||
"@electron-forge/shared-types": "7.3.0"
|
||||
"@electron-forge/shared-types": "7.3.1"
|
||||
},
|
||||
"engines": {
|
||||
"node": ">= 16.4.0"
|
||||
}
|
||||
},
|
||||
"node_modules/@electron-forge/publisher-base": {
|
||||
"version": "7.3.0",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/publisher-base/-/publisher-base-7.3.0.tgz",
|
||||
"integrity": "sha512-iO8QuM0zTLcEA0/7adEUOzMrhu/h6Qk9UiWNUllBctZXZ+FO0CbAY7eGzOgjOKqH5akbEKHwCSRnjrFt91QpQg==",
|
||||
"version": "7.3.1",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/publisher-base/-/publisher-base-7.3.1.tgz",
|
||||
"integrity": "sha512-2JMTbUfgBi11AkprTclyeGhn4dwN0rsDVzHYLwOZ08cWSMhvQ0zy/YznI4Yfl9pptirb9I9X8fLQMEK4XbeBQA==",
|
||||
"dev": true,
|
||||
"dependencies": {
|
||||
"@electron-forge/shared-types": "7.3.0"
|
||||
"@electron-forge/shared-types": "7.3.1"
|
||||
},
|
||||
"engines": {
|
||||
"node": ">= 16.4.0"
|
||||
}
|
||||
},
|
||||
"node_modules/@electron-forge/shared-types": {
|
||||
"version": "7.3.0",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/shared-types/-/shared-types-7.3.0.tgz",
|
||||
"integrity": "sha512-+YGOTGUGVrcaRm9zO3xsWSj2GS9iVY6E1WTG0vD2OxZtdEGcdy3hZryV72f5gH+qeZZvujYSR2s7VvZjhFEHaQ==",
|
||||
"version": "7.3.1",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/shared-types/-/shared-types-7.3.1.tgz",
|
||||
"integrity": "sha512-yRW3UWd+AwtK1UrZxWCtxqnD1lF6e+1GWXdgR186/UX2CMy+jVzUtL4Xk+xMKrLgiVKZglVbTdee1cEb6egtVw==",
|
||||
"dev": true,
|
||||
"dependencies": {
|
||||
"@electron-forge/tracer": "7.3.0",
|
||||
"@electron/packager": "^18.1.2",
|
||||
"@electron-forge/tracer": "7.3.1",
|
||||
"@electron/packager": "^18.1.3",
|
||||
"@electron/rebuild": "^3.2.10",
|
||||
"listr2": "^5.0.3"
|
||||
},
|
||||
|
@ -283,12 +283,12 @@
|
|||
}
|
||||
},
|
||||
"node_modules/@electron-forge/template-base": {
|
||||
"version": "7.3.0",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/template-base/-/template-base-7.3.0.tgz",
|
||||
"integrity": "sha512-Lf0fupMzuO9XuBOaWoQ5QljjQ89B7TYU40+eEUvxnIMNAfnU3n+cfhC4xGLldmh+LYRuotB1jJitX79BwRqzIA==",
|
||||
"version": "7.3.1",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/template-base/-/template-base-7.3.1.tgz",
|
||||
"integrity": "sha512-iGzjWeZlxoIdZMaLu4ABwG4AzI2/QEUMM9817mMVb24+7ZUTtrP8WJWkpsJjcEjXtb1oyt3CRoNqQt+iH6H1BA==",
|
||||
"dev": true,
|
||||
"dependencies": {
|
||||
"@electron-forge/shared-types": "7.3.0",
|
||||
"@electron-forge/shared-types": "7.3.1",
|
||||
"@malept/cross-spawn-promise": "^2.0.0",
|
||||
"debug": "^4.3.1",
|
||||
"fs-extra": "^10.0.0",
|
||||
|
@ -299,13 +299,13 @@
|
|||
}
|
||||
},
|
||||
"node_modules/@electron-forge/template-vite": {
|
||||
"version": "7.3.0",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/template-vite/-/template-vite-7.3.0.tgz",
|
||||
"integrity": "sha512-4vdOLmd0/rThA9lO/Tf16oCoDBPWGLRZZF+XM+ECPDfaL0CbFNoEa/NLrr6T/2D6IlV5+GnmVjz29LlVOFUB7w==",
|
||||
"version": "7.3.1",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/template-vite/-/template-vite-7.3.1.tgz",
|
||||
"integrity": "sha512-r1PFPZ2Y7t4EDte2HckTUiXQY1L++wofolm6TRzVv/h5ZViHq8vNBWvXTyZNtZOtqIErIRbGXHL1DbiRlgOMTg==",
|
||||
"dev": true,
|
||||
"dependencies": {
|
||||
"@electron-forge/shared-types": "7.3.0",
|
||||
"@electron-forge/template-base": "7.3.0",
|
||||
"@electron-forge/shared-types": "7.3.1",
|
||||
"@electron-forge/template-base": "7.3.1",
|
||||
"fs-extra": "^10.0.0"
|
||||
},
|
||||
"engines": {
|
||||
|
@ -313,13 +313,13 @@
|
|||
}
|
||||
},
|
||||
"node_modules/@electron-forge/template-vite-typescript": {
|
||||
"version": "7.3.0",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/template-vite-typescript/-/template-vite-typescript-7.3.0.tgz",
|
||||
"integrity": "sha512-4gVlJihXLM+r6GBOCeO6mSv5vZImew9Vp/xFfxMrf3nDThMCnA6HYLIGA361ZTbn4z3ARquXPo6Vsm7/s4ykbw==",
|
||||
"version": "7.3.1",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/template-vite-typescript/-/template-vite-typescript-7.3.1.tgz",
|
||||
"integrity": "sha512-YS2arQENkpBbpFXk7SlAulK77OMLgcutjmZd0jW9Z/PUCUo9rdTW9QmlCNFz37tRHvwpClJcTcAoKpCoJUrIVA==",
|
||||
"dev": true,
|
||||
"dependencies": {
|
||||
"@electron-forge/shared-types": "7.3.0",
|
||||
"@electron-forge/template-base": "7.3.0",
|
||||
"@electron-forge/shared-types": "7.3.1",
|
||||
"@electron-forge/template-base": "7.3.1",
|
||||
"fs-extra": "^10.0.0"
|
||||
},
|
||||
"engines": {
|
||||
|
@ -327,13 +327,13 @@
|
|||
}
|
||||
},
|
||||
"node_modules/@electron-forge/template-webpack": {
|
||||
"version": "7.3.0",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/template-webpack/-/template-webpack-7.3.0.tgz",
|
||||
"integrity": "sha512-5Cv0g+AHdEI2R4hPI38PzWTnqUwqpM36jpQgkXV1RnL3V9FvNuza/w9RLMj5bhGzB0j5M4bVbcnglMX0pDvVBQ==",
|
||||
"version": "7.3.1",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/template-webpack/-/template-webpack-7.3.1.tgz",
|
||||
"integrity": "sha512-SlzfFsOUVsx9Yk6Hhqqsw33s1/J1cx7eGkc9AVASKZnGHnFDGYUVyTr1ueR7SFQwZd5TOs7OISQ6sL2GQa4Icg==",
|
||||
"dev": true,
|
||||
"dependencies": {
|
||||
"@electron-forge/shared-types": "7.3.0",
|
||||
"@electron-forge/template-base": "7.3.0",
|
||||
"@electron-forge/shared-types": "7.3.1",
|
||||
"@electron-forge/template-base": "7.3.1",
|
||||
"fs-extra": "^10.0.0"
|
||||
},
|
||||
"engines": {
|
||||
|
@ -341,13 +341,13 @@
|
|||
}
|
||||
},
|
||||
"node_modules/@electron-forge/template-webpack-typescript": {
|
||||
"version": "7.3.0",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/template-webpack-typescript/-/template-webpack-typescript-7.3.0.tgz",
|
||||
"integrity": "sha512-eiBhsY/LUaV1vIy/PZqnmkxWyjEyN/PsXyq79lr1nuOKrqkVgZUe/IdvtNxr8wvPoKSScORNLHjiD/C2Jp74HA==",
|
||||
"version": "7.3.1",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/template-webpack-typescript/-/template-webpack-typescript-7.3.1.tgz",
|
||||
"integrity": "sha512-cCFAuiKiKCNAJTXOgA3NTLAU6VQ0uYtGa6WiI8q5tK7d34Ef6zEuCKt5opI4zKXVdFrE0vYE0PBHH/M++z1g1w==",
|
||||
"dev": true,
|
||||
"dependencies": {
|
||||
"@electron-forge/shared-types": "7.3.0",
|
||||
"@electron-forge/template-base": "7.3.0",
|
||||
"@electron-forge/shared-types": "7.3.1",
|
||||
"@electron-forge/template-base": "7.3.1",
|
||||
"fs-extra": "^10.0.0"
|
||||
},
|
||||
"engines": {
|
||||
|
@ -355,9 +355,9 @@
|
|||
}
|
||||
},
|
||||
"node_modules/@electron-forge/tracer": {
|
||||
"version": "7.3.0",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/tracer/-/tracer-7.3.0.tgz",
|
||||
"integrity": "sha512-FS7ABTm52BMP2BlR/pDmUIKtH9NI1i+BBJuKke58KguToBRuvAX1cLt0Hhkq4HlqYR9fNjRoCo1vrK4OBb0Bew==",
|
||||
"version": "7.3.1",
|
||||
"resolved": "https://registry.npmjs.org/@electron-forge/tracer/-/tracer-7.3.1.tgz",
|
||||
"integrity": "sha512-Jz6SgnHZ2Gk4l7WRu/rLyQTe6F23dXcTNsjI5gtUEJxjjd2K9L0UoxVcGikA7SEMUufaPyskSJfrW7NSZ4s43Q==",
|
||||
"dev": true,
|
||||
"dependencies": {
|
||||
"chrome-trace-event": "^1.0.3"
|
||||
|
@ -367,9 +367,9 @@
|
|||
}
|
||||
},
|
||||
"node_modules/@electron/asar": {
|
||||
"version": "3.2.8",
|
||||
"resolved": "https://registry.npmjs.org/@electron/asar/-/asar-3.2.8.tgz",
|
||||
"integrity": "sha512-cmskk5M06ewHMZAplSiF4AlME3IrnnZhKnWbtwKVLRkdJkKyUVjMLhDIiPIx/+6zQWVlKX/LtmK9xDme7540Sg==",
|
||||
"version": "3.2.9",
|
||||
"resolved": "https://registry.npmjs.org/@electron/asar/-/asar-3.2.9.tgz",
|
||||
"integrity": "sha512-Vu2P3X2gcZ3MY9W7yH72X9+AMXwUQZEJBrsPIbX0JsdllLtoh62/Q8Wg370/DawIEVKOyfD6KtTLo645ezqxUA==",
|
||||
"dev": true,
|
||||
"dependencies": {
|
||||
"commander": "^5.0.0",
|
||||
|
@ -487,9 +487,9 @@
|
|||
}
|
||||
},
|
||||
"node_modules/@electron/osx-sign": {
|
||||
"version": "1.0.5",
|
||||
"resolved": "https://registry.npmjs.org/@electron/osx-sign/-/osx-sign-1.0.5.tgz",
|
||||
"integrity": "sha512-k9ZzUQtamSoweGQDV2jILiRIHUu7lYlJ3c6IEmjv1hC17rclE+eb9U+f6UFlOOETo0JzY1HNlXy4YOlCvl+Lww==",
|
||||
"version": "1.1.0",
|
||||
"resolved": "https://registry.npmjs.org/@electron/osx-sign/-/osx-sign-1.1.0.tgz",
|
||||
"integrity": "sha512-9xxNAyTu2YEAfn2TOQXC5fcTZ9hxVT/zAgWOONpOvxivv5rU97RldGbJrxz+OBKXGAiQRJUYOY07mJI++S/iYw==",
|
||||
"dev": true,
|
||||
"dependencies": {
|
||||
"compare-version": "^0.1.2",
|
||||
|
@ -675,9 +675,9 @@
|
|||
}
|
||||
},
|
||||
"node_modules/@electron/windows-sign": {
|
||||
"version": "1.1.1",
|
||||
"resolved": "https://registry.npmjs.org/@electron/windows-sign/-/windows-sign-1.1.1.tgz",
|
||||
"integrity": "sha512-g8/atfOCKuuGedjVE6Xu/rlBtJvfDrmBH9UokBrjrvBVWdVz3SGV7DTjPTLvl7F+XUlmqj4genub62r3jKHIHw==",
|
||||
"version": "1.1.2",
|
||||
"resolved": "https://registry.npmjs.org/@electron/windows-sign/-/windows-sign-1.1.2.tgz",
|
||||
"integrity": "sha512-eXEiZjDtxW3QORCWfRUarANPRTlH9B6At4jqBZJ0NzokSGutXQUVLPA6WmGpIhDW6w2yCMdHW1EJd1HrXtU5sg==",
|
||||
"dev": true,
|
||||
"dependencies": {
|
||||
"cross-dirname": "^0.1.0",
|
||||
|
@ -690,7 +690,7 @@
|
|||
"electron-windows-sign": "bin/electron-windows-sign.js"
|
||||
},
|
||||
"engines": {
|
||||
"node": ">=16.0.0"
|
||||
"node": ">=14.14"
|
||||
}
|
||||
},
|
||||
"node_modules/@electron/windows-sign/node_modules/fs-extra": {
|
||||
|
@ -1094,9 +1094,9 @@
|
|||
"optional": true
|
||||
},
|
||||
"node_modules/@types/node": {
|
||||
"version": "18.19.18",
|
||||
"resolved": "https://registry.npmjs.org/@types/node/-/node-18.19.18.tgz",
|
||||
"integrity": "sha512-80CP7B8y4PzZF0GWx15/gVWRrB5y/bIjNI84NK3cmQJu0WZwvmj2WMA5LcofQFVfLqqCSp545+U2LsrVzX36Zg==",
|
||||
"version": "18.19.26",
|
||||
"resolved": "https://registry.npmjs.org/@types/node/-/node-18.19.26.tgz",
|
||||
"integrity": "sha512-+wiMJsIwLOYCvUqSdKTrfkS8mpTp+MPINe6+Np4TAGFWWRWiBQ5kSq9nZGCSPkzx9mvT+uEukzpX4MOSCydcvw==",
|
||||
"dependencies": {
|
||||
"undici-types": "~5.26.4"
|
||||
}
|
||||
|
@ -2657,9 +2657,9 @@
|
|||
"integrity": "sha512-3NdhDuEXnfun/z7x9GOElY49LoqVHoGScmOKwmxhsS8N5Y+Z8KyPPDnaSzqWgYt/ji4mqwfTS34Htrk0zPIXVg=="
|
||||
},
|
||||
"node_modules/detect-libc": {
|
||||
"version": "2.0.2",
|
||||
"resolved": "https://registry.npmjs.org/detect-libc/-/detect-libc-2.0.2.tgz",
|
||||
"integrity": "sha512-UX6sGumvvqSaXgdKGUsgZWqcUyIXZ/vZTrlRT/iobiKhGL0zL4d3osHj3uqllWJK+i+sixDS/3COVEOFbupFyw==",
|
||||
"version": "2.0.3",
|
||||
"resolved": "https://registry.npmjs.org/detect-libc/-/detect-libc-2.0.3.tgz",
|
||||
"integrity": "sha512-bwy0MGW55bG41VqxxypOsdSdGqLwXPI/focwgTYCFMbdUiBAxLg9CFzG08sz2aqzknwiX7Hkl0bQENjg8iLByw==",
|
||||
"dev": true,
|
||||
"engines": {
|
||||
"node": ">=8"
|
||||
|
@ -3071,9 +3071,9 @@
|
|||
"integrity": "sha512-Tpp60P6IUJDTuOq/5Z8cdskzJujfwqfOTkrwIwj7IRISpnkJnT6SyJ4PCPnGMoFjC9ddhal5KVIYtAt97ix05A=="
|
||||
},
|
||||
"node_modules/electron-store": {
|
||||
"version": "8.1.0",
|
||||
"resolved": "https://registry.npmjs.org/electron-store/-/electron-store-8.1.0.tgz",
|
||||
"integrity": "sha512-2clHg/juMjOH0GT9cQ6qtmIvK183B39ZXR0bUoPwKwYHJsEF3quqyDzMFUAu+0OP8ijmN2CbPRAelhNbWUbzwA==",
|
||||
"version": "8.2.0",
|
||||
"resolved": "https://registry.npmjs.org/electron-store/-/electron-store-8.2.0.tgz",
|
||||
"integrity": "sha512-ukLL5Bevdil6oieAOXz3CMy+OgaItMiVBg701MNlG6W5RaC0AHN7rvlqTCmeb6O7jP0Qa1KKYTE0xV0xbhF4Hw==",
|
||||
"dependencies": {
|
||||
"conf": "^10.2.0",
|
||||
"type-fest": "^2.17.0"
|
||||
|
@ -3095,9 +3095,9 @@
|
|||
}
|
||||
},
|
||||
"node_modules/electron-winstaller": {
|
||||
"version": "5.2.2",
|
||||
"resolved": "https://registry.npmjs.org/electron-winstaller/-/electron-winstaller-5.2.2.tgz",
|
||||
"integrity": "sha512-nw+SbS0DA6SF8bEkcL4SqtPOoLKc5JkEXAz7kzdzz22rY12PZRtTn9zpztbwy+xrLqSBBFR1u0bdvNLpvlmrkw==",
|
||||
"version": "5.3.0",
|
||||
"resolved": "https://registry.npmjs.org/electron-winstaller/-/electron-winstaller-5.3.0.tgz",
|
||||
"integrity": "sha512-ml77/OmeeLFFc+dk3YCwPQrl8rthwYcAea6mMZPFq7cGXlpWyRmmT0LY73XdCukPnevguXJFs+4Xu+aGHJwFDA==",
|
||||
"dev": true,
|
||||
"hasInstallScript": true,
|
||||
"optional": true,
|
||||
|
@ -3110,6 +3110,9 @@
|
|||
},
|
||||
"engines": {
|
||||
"node": ">=8.0.0"
|
||||
},
|
||||
"optionalDependencies": {
|
||||
"@electron/windows-sign": "^1.1.2"
|
||||
}
|
||||
},
|
||||
"node_modules/electron-winstaller/node_modules/fs-extra": {
|
||||
|
@ -4288,9 +4291,9 @@
|
|||
"integrity": "sha512-8Rf9Y83NBReMnx0gFzA8JImQACstCYWUplepDa9xprwwtmgEZUF0h/i5xSA625zB/I37EtrswSST6OXxwaaIJQ=="
|
||||
},
|
||||
"node_modules/hasown": {
|
||||
"version": "2.0.1",
|
||||
"resolved": "https://registry.npmjs.org/hasown/-/hasown-2.0.1.tgz",
|
||||
"integrity": "sha512-1/th4MHjnwncwXsIW6QMzlvYL9kG5e/CpVvLRZe4XPa8TOUNbCELqmvhDmnkNsAjwaG4+I8gJJL0JBvTTLO9qA==",
|
||||
"version": "2.0.2",
|
||||
"resolved": "https://registry.npmjs.org/hasown/-/hasown-2.0.2.tgz",
|
||||
"integrity": "sha512-0hJU9SCPvmMzIBdZFqNPXWa6dqh7WdH0cII9y+CyS8rG3nL48Bclra9HmKhVVUHyPWNH5Y7xDwAB7bfgSjkUMQ==",
|
||||
"dependencies": {
|
||||
"function-bind": "^1.1.2"
|
||||
},
|
||||
|
@ -4435,9 +4438,9 @@
|
|||
}
|
||||
},
|
||||
"node_modules/i18next": {
|
||||
"version": "23.10.0",
|
||||
"resolved": "https://registry.npmjs.org/i18next/-/i18next-23.10.0.tgz",
|
||||
"integrity": "sha512-/TgHOqsa7/9abUKJjdPeydoyDc0oTi/7u9F8lMSj6ufg4cbC1Oj3f/Jja7zj7WRIhEQKB7Q4eN6y68I9RDxxGQ==",
|
||||
"version": "23.10.1",
|
||||
"resolved": "https://registry.npmjs.org/i18next/-/i18next-23.10.1.tgz",
|
||||
"integrity": "sha512-NDiIzFbcs3O9PXpfhkjyf7WdqFn5Vq6mhzhtkXzj51aOcNuPNcTwuYNuXCpHsanZGHlHKL35G7huoFeVic1hng==",
|
||||
"funding": [
|
||||
{
|
||||
"type": "individual",
|
||||
|
@ -7026,16 +7029,16 @@
|
|||
"integrity": "sha512-KiKBS8AnWGEyLzofFfmvKwpdPzqiy16LvQfK3yv/fVH7Bj13/wl3JSR1J+rfgRE9q7xUJK4qvgS8raSOeLUehw=="
|
||||
},
|
||||
"node_modules/set-function-length": {
|
||||
"version": "1.2.1",
|
||||
"resolved": "https://registry.npmjs.org/set-function-length/-/set-function-length-1.2.1.tgz",
|
||||
"integrity": "sha512-j4t6ccc+VsKwYHso+kElc5neZpjtq9EnRICFZtWyBsLojhmeF/ZBd/elqm22WJh/BziDe/SBiOeAt0m2mfLD0g==",
|
||||
"version": "1.2.2",
|
||||
"resolved": "https://registry.npmjs.org/set-function-length/-/set-function-length-1.2.2.tgz",
|
||||
"integrity": "sha512-pgRc4hJ4/sNjWCSS9AmnS40x3bNMDTknHgL5UaMBTMyJnU90EgWh1Rz+MC9eFu4BuN/UwZjKQuY/1v3rM7HMfg==",
|
||||
"dependencies": {
|
||||
"define-data-property": "^1.1.2",
|
||||
"define-data-property": "^1.1.4",
|
||||
"es-errors": "^1.3.0",
|
||||
"function-bind": "^1.1.2",
|
||||
"get-intrinsic": "^1.2.3",
|
||||
"get-intrinsic": "^1.2.4",
|
||||
"gopd": "^1.0.1",
|
||||
"has-property-descriptors": "^1.0.1"
|
||||
"has-property-descriptors": "^1.0.2"
|
||||
},
|
||||
"engines": {
|
||||
"node": ">= 0.4"
|
||||
|
@ -7586,16 +7589,13 @@
|
|||
}
|
||||
},
|
||||
"node_modules/tmp-promise/node_modules/tmp": {
|
||||
"version": "0.2.1",
|
||||
"resolved": "https://registry.npmjs.org/tmp/-/tmp-0.2.1.tgz",
|
||||
"integrity": "sha512-76SUhtfqR2Ijn+xllcI5P1oyannHNHByD80W1q447gU3mp9G9PSpGdWmjUOHRDPiHYacIk66W7ubDTuPF3BEtQ==",
|
||||
"version": "0.2.3",
|
||||
"resolved": "https://registry.npmjs.org/tmp/-/tmp-0.2.3.tgz",
|
||||
"integrity": "sha512-nZD7m9iCPC5g0pYmcaxogYKggSfLsdxl8of3Q/oIbqCqLLIO9IAF0GWjX1z9NZRHPiXv8Wex4yDCaZsgEw0Y8w==",
|
||||
"dev": true,
|
||||
"optional": true,
|
||||
"dependencies": {
|
||||
"rimraf": "^3.0.0"
|
||||
},
|
||||
"engines": {
|
||||
"node": ">=8.17.0"
|
||||
"node": ">=14.14"
|
||||
}
|
||||
},
|
||||
"node_modules/to-array": {
|
||||
|
@ -7850,9 +7850,9 @@
|
|||
}
|
||||
},
|
||||
"node_modules/usb": {
|
||||
"version": "2.11.0",
|
||||
"resolved": "https://registry.npmjs.org/usb/-/usb-2.11.0.tgz",
|
||||
"integrity": "sha512-u5+NZ6DtoW8TIBtuSArQGAZZ/K15i3lYvZBAYmcgI+RcDS9G50/KPrUd3CrU8M92ahyCvg5e0gc8BDvr5Hwejg==",
|
||||
"version": "2.12.1",
|
||||
"resolved": "https://registry.npmjs.org/usb/-/usb-2.12.1.tgz",
|
||||
"integrity": "sha512-hgtoSQUFuMXVJBApelpUTiX7ZB83MQCbYeHTBsHftA2JG7YZ76ycwIgKQhkhKqVY76C8K6xJscHpF7Ep0eG3pQ==",
|
||||
"hasInstallScript": true,
|
||||
"dependencies": {
|
||||
"@types/w3c-web-usb": "^1.0.6",
|
||||
|
|
|
@ -6,7 +6,7 @@
|
|||
@import 'font-awesome/css/font-awesome.css';
|
||||
@import 'dropdown-lists/css/style_lists.css';
|
||||
@import '../../js/libraries/switchery/switchery.css';
|
||||
@import '../../js/libraries/jbox/jBox.css';
|
||||
@import '../../js/libraries/jBox/jBox.css';
|
||||
@import 'logic.css';
|
||||
@import 'defaults_dialog.css';
|
||||
@import './../../node_modules/openlayers/dist/ol.css';
|
||||
|
|
|
@ -1,6 +1,16 @@
|
|||
/*global chrome */
|
||||
'use strict';
|
||||
|
||||
const path = require('path');
|
||||
|
||||
const MSPChainerClass = require('./../js/msp/MSPchainer');
|
||||
const mspHelper = require('./../js/msp/MSPHelper');
|
||||
const MSPCodes = require('./../js/msp/MSPCodes');
|
||||
const MSP = require('./../js/msp');
|
||||
const { GUI, TABS } = require('./../js/gui');
|
||||
const FC = require('./../js/fc');
|
||||
const i18n = require('./../js/localization');
|
||||
|
||||
TABS.calibration = {};
|
||||
|
||||
TABS.calibration.model = (function () {
|
||||
|
@ -16,7 +26,7 @@ TABS.calibration.model = (function () {
|
|||
} else {
|
||||
var count = 0;
|
||||
for (var i = 0; i < 6; i++) {
|
||||
if (CALIBRATION_DATA.acc['Pos' + i] === 1) {
|
||||
if (FC.CALIBRATION_DATA.acc['Pos' + i] === 1) {
|
||||
count++;
|
||||
}
|
||||
}
|
||||
|
@ -81,14 +91,14 @@ TABS.calibration.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function loadHtml() {
|
||||
GUI.load(path.join(__dirname, "tabs/calibration.html"), processHtml);
|
||||
GUI.load(path.join(__dirname, "calibration.html"), processHtml);
|
||||
}
|
||||
|
||||
function updateCalibrationSteps() {
|
||||
for (var i = 0; i < 6; i++) {
|
||||
var $element = $('[data-step="' + (i + 1) + '"]');
|
||||
|
||||
if (CALIBRATION_DATA.acc['Pos' + i] === 0) {
|
||||
if (FC.CALIBRATION_DATA.acc['Pos' + i] === 0) {
|
||||
$element.removeClass('finished').removeClass('active');
|
||||
} else {
|
||||
$element.addClass("finished").removeClass('active');
|
||||
|
@ -99,12 +109,12 @@ TABS.calibration.initialize = function (callback) {
|
|||
function updateSensorData() {
|
||||
var pos = ['X', 'Y', 'Z'];
|
||||
pos.forEach(function (item) {
|
||||
$('[name=accGain' + item + ']').val(CALIBRATION_DATA.accGain[item]);
|
||||
$('[name=accZero' + item + ']').val(CALIBRATION_DATA.accZero[item]);
|
||||
$('[name=Mag' + item + ']').val(CALIBRATION_DATA.magZero[item]);
|
||||
$('[name=MagGain' + item + ']').val(CALIBRATION_DATA.magGain[item]);
|
||||
$('[name=accGain' + item + ']').val(FC.CALIBRATION_DATA.accGain[item]);
|
||||
$('[name=accZero' + item + ']').val(FC.CALIBRATION_DATA.accZero[item]);
|
||||
$('[name=Mag' + item + ']').val(FC.CALIBRATION_DATA.magZero[item]);
|
||||
$('[name=MagGain' + item + ']').val(FC.CALIBRATION_DATA.magGain[item]);
|
||||
});
|
||||
$('[name=OpflowScale]').val(CALIBRATION_DATA.opflow.Scale);
|
||||
$('[name=OpflowScale]').val(FC.CALIBRATION_DATA.opflow.Scale);
|
||||
updateCalibrationSteps();
|
||||
}
|
||||
|
||||
|
@ -128,8 +138,8 @@ TABS.calibration.initialize = function (callback) {
|
|||
|
||||
if (TABS.calibration.model.getStep() === null) {
|
||||
for (var i = 0; i < 6; i++) {
|
||||
if (CALIBRATION_DATA.acc['Pos' + i] === 1) {
|
||||
CALIBRATION_DATA.acc['Pos' + i] = 0;
|
||||
if (FC.CALIBRATION_DATA.acc['Pos' + i] === 1) {
|
||||
FC.CALIBRATION_DATA.acc['Pos' + i] = 0;
|
||||
}
|
||||
}
|
||||
updateCalibrationSteps();
|
||||
|
@ -203,8 +213,8 @@ TABS.calibration.initialize = function (callback) {
|
|||
function resetAccCalibration() {
|
||||
var pos = ['X', 'Y', 'Z'];
|
||||
pos.forEach(function (item) {
|
||||
CALIBRATION_DATA.accGain[item] = 4096;
|
||||
CALIBRATION_DATA.accZero[item] = 0;
|
||||
FC.CALIBRATION_DATA.accGain[item] = 4096;
|
||||
FC.CALIBRATION_DATA.accZero[item] = 0;
|
||||
});
|
||||
|
||||
saveChainer.execute();
|
||||
|
@ -212,16 +222,16 @@ TABS.calibration.initialize = function (callback) {
|
|||
|
||||
function processHtml() {
|
||||
$('#calibrateButtonSave').on('click', function () {
|
||||
CALIBRATION_DATA.opflow.Scale = parseFloat($('[name=OpflowScale]').val());
|
||||
FC.CALIBRATION_DATA.opflow.Scale = parseFloat($('[name=OpflowScale]').val());
|
||||
saveChainer.execute();
|
||||
});
|
||||
|
||||
if (SENSOR_CONFIG.magnetometer === 0) {
|
||||
if (FC.SENSOR_CONFIG.magnetometer === 0) {
|
||||
//Comment for test
|
||||
$('#mag_btn, #mag-calibrated-data').css('pointer-events', 'none').css('opacity', '0.4');
|
||||
}
|
||||
|
||||
if (SENSOR_CONFIG.opflow === 0) {
|
||||
if (FC.SENSOR_CONFIG.opflow === 0) {
|
||||
//Comment for test
|
||||
$('#opflow_btn, #opflow-calibrated-data').css('pointer-events', 'none').css('opacity', '0.4');
|
||||
}
|
||||
|
|
159
tabs/mixer.js
159
tabs/mixer.js
|
@ -1,6 +1,19 @@
|
|||
/*global $,helper,mspHelper,MSP,GUI,SERVO_RULES,MOTOR_RULES,MIXER_CONFIG,LOGIC_CONDITIONS,TABS,ServoMixRule*/
|
||||
'use strict';
|
||||
|
||||
const path = require('path');
|
||||
|
||||
const MSPChainerClass = require('./../js/msp/MSPchainer');
|
||||
const mspHelper = require('./../js/msp/MSPHelper');
|
||||
const MSPCodes = require('./../js/msp/MSPCodes');
|
||||
const MSP = require('./../js/msp');
|
||||
const { GUI, TABS } = require('./../js/gui');
|
||||
const FC = require('./../js/fc');
|
||||
const i18n = require('./../js/localization');
|
||||
const { mixer, platform, PLATFORM, INPUT, STABILIZED } = require('./../js/model');
|
||||
const Settings = require('./../js/settings');
|
||||
const mspBalancedInterval = require('./../js/msp_balanced_interval');
|
||||
const jBox = require('../js/libraries/jBox/jBox.min.js')
|
||||
|
||||
TABS.mixer = {};
|
||||
|
||||
TABS.mixer.initialize = function (callback, scrollPosition) {
|
||||
|
@ -64,11 +77,11 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
function loadHtml() {
|
||||
GUI.load(path.join(__dirname, "tabs/mixer.html"), Settings.processHtml(processHtml));
|
||||
GUI.load(path.join(__dirname, "mixer.html"), Settings.processHtml(processHtml));
|
||||
}
|
||||
|
||||
function renderOutputTable() {
|
||||
let outputCount = OUTPUT_MAPPING.getOutputCount(),
|
||||
let outputCount = FC.OUTPUT_MAPPING.getOutputCount(),
|
||||
$outputRow = $('#output-row'),
|
||||
$functionRow = $('#function-row');
|
||||
|
||||
|
@ -77,8 +90,8 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
|
||||
for (let i = 1; i <= outputCount; i++) {
|
||||
|
||||
let timerId = OUTPUT_MAPPING.getTimerId(i - 1);
|
||||
let color = OUTPUT_MAPPING.getOutputTimerColor(i - 1);
|
||||
let timerId = FC.OUTPUT_MAPPING.getTimerId(i - 1);
|
||||
let color = FC.OUTPUT_MAPPING.getOutputTimerColor(i - 1);
|
||||
|
||||
$outputRow.append('<td style="background-color: ' + color + '">S' + i + ' (Timer ' + (timerId + 1) + ')</td>');
|
||||
$functionRow.append('<td id="function-' + i +'">-</td>');
|
||||
|
@ -89,7 +102,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
function updateTimerOverride() {
|
||||
let timers = OUTPUT_MAPPING.getUsedTimerIds();
|
||||
let timers = FC.OUTPUT_MAPPING.getUsedTimerIds();
|
||||
|
||||
for(let i =0; i < timers.length;++i) {
|
||||
let timerId = timers[i];
|
||||
|
@ -97,25 +110,25 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
if(!$select) {
|
||||
continue;
|
||||
}
|
||||
OUTPUT_MAPPING.setTimerOverride(timerId, $select.val());
|
||||
FC.OUTPUT_MAPPING.setTimerOverride(timerId, $select.val());
|
||||
}
|
||||
}
|
||||
|
||||
function renderTimerOverride() {
|
||||
let outputCount = OUTPUT_MAPPING.getOutputCount(),
|
||||
let outputCount = FC.OUTPUT_MAPPING.getOutputCount(),
|
||||
$container = $('#timerOutputsList'), timers = {};
|
||||
|
||||
|
||||
let usedTimers = OUTPUT_MAPPING.getUsedTimerIds();
|
||||
let usedTimers = FC.OUTPUT_MAPPING.getUsedTimerIds();
|
||||
|
||||
for (let t of usedTimers) {
|
||||
var usageMode = OUTPUT_MAPPING.getTimerOverride(t);
|
||||
var usageMode = FC.OUTPUT_MAPPING.getTimerOverride(t);
|
||||
$container.append(
|
||||
'<div class="select" style="padding: 5px; margin: 1px; background-color: ' + OUTPUT_MAPPING.getTimerColor(t) + '">' +
|
||||
'<div class="select" style="padding: 5px; margin: 1px; background-color: ' + FC.OUTPUT_MAPPING.getTimerColor(t) + '">' +
|
||||
'<select id="timer-output-' + t + '">' +
|
||||
'<option value=' + OUTPUT_MAPPING.TIMER_OUTPUT_MODE_AUTO + '' + (usageMode == OUTPUT_MAPPING.TIMER_OUTPUT_MODE_AUTO ? ' selected' : '')+ '>AUTO</option>'+
|
||||
'<option value=' + OUTPUT_MAPPING.TIMER_OUTPUT_MODE_MOTORS + '' + (usageMode == OUTPUT_MAPPING.TIMER_OUTPUT_MODE_MOTORS ? ' selected' : '')+ '>MOTORS</option>'+
|
||||
'<option value=' + OUTPUT_MAPPING.TIMER_OUTPUT_MODE_SERVOS + '' + (usageMode == OUTPUT_MAPPING.TIMER_OUTPUT_MODE_SERVOS ? ' selected' : '')+ '>SERVOS</option>'+
|
||||
'<option value=' + FC.OUTPUT_MAPPING.TIMER_OUTPUT_MODE_AUTO + '' + (usageMode == FC.OUTPUT_MAPPING.TIMER_OUTPUT_MODE_AUTO ? ' selected' : '')+ '>AUTO</option>'+
|
||||
'<option value=' + FC.OUTPUT_MAPPING.TIMER_OUTPUT_MODE_MOTORS + '' + (usageMode == FC.OUTPUT_MAPPING.TIMER_OUTPUT_MODE_MOTORS ? ' selected' : '')+ '>MOTORS</option>'+
|
||||
'<option value=' + FC.OUTPUT_MAPPING.TIMER_OUTPUT_MODE_SERVOS + '' + (usageMode == FC.OUTPUT_MAPPING.TIMER_OUTPUT_MODE_SERVOS ? ' selected' : '')+ '>SERVOS</option>'+
|
||||
'</select>' +
|
||||
'<label for="timer-output-' + t + '">' +
|
||||
'<span> Timer ' + (parseInt(t) + 1) + '</span>' +
|
||||
|
@ -127,13 +140,13 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
function renderOutputMapping() {
|
||||
let outputMap = OUTPUT_MAPPING.getOutputTable(
|
||||
MIXER_CONFIG.platformType == PLATFORM.MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM.TRICOPTER,
|
||||
MOTOR_RULES.getNumberOfConfiguredMotors(),
|
||||
SERVO_RULES.getUsedServoIndexes()
|
||||
let outputMap = FC.OUTPUT_MAPPING.getOutputTable(
|
||||
FC.MIXER_CONFIG.platformType == PLATFORM.MULTIROTOR || FC.MIXER_CONFIG.platformType == PLATFORM.TRICOPTER,
|
||||
FC.MOTOR_RULES.getNumberOfConfiguredMotors(),
|
||||
FC.SERVO_RULES.getUsedServoIndexes()
|
||||
);
|
||||
|
||||
for (let i = 1; i <= OUTPUT_MAPPING.getOutputCount(); i++) {
|
||||
for (let i = 1; i <= FC.OUTPUT_MAPPING.getOutputCount(); i++) {
|
||||
$('#function-' + i).html(outputMap[i - 1]);
|
||||
}
|
||||
|
||||
|
@ -150,18 +163,18 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
$(this).css("color", "");
|
||||
});
|
||||
|
||||
if (MIXER_CONFIG.platformType == PLATFORM.AIRPLANE) {
|
||||
if (FC.MIXER_CONFIG.platformType == PLATFORM.AIRPLANE) {
|
||||
if (outputMap != null && currentMixerPreset.hasOwnProperty('imageOutputsNumbers')) {
|
||||
let outputPad = 1;
|
||||
let outputArea = null;
|
||||
let inputBoxes = null;
|
||||
let surfaces = {
|
||||
aileronSet: helper.mixer.countSurfaceType(currentMixerPreset, INPUT.STABILIZED_ROLL),
|
||||
elevatorSet: helper.mixer.countSurfaceType(currentMixerPreset, INPUT.STABILIZED_PITCH),
|
||||
rudderSet: helper.mixer.countSurfaceType(currentMixerPreset, INPUT.STABILIZED_YAW),
|
||||
aileronSet: mixer.countSurfaceType(currentMixerPreset, INPUT.STABILIZED_ROLL),
|
||||
elevatorSet: mixer.countSurfaceType(currentMixerPreset, INPUT.STABILIZED_PITCH),
|
||||
rudderSet: mixer.countSurfaceType(currentMixerPreset, INPUT.STABILIZED_YAW),
|
||||
};
|
||||
let motors = [];
|
||||
let servoRules = SERVO_RULES;
|
||||
let servoRules = FC.SERVO_RULES;
|
||||
|
||||
for (let omIndex of outputMap) {
|
||||
if (omIndex != '-') {
|
||||
|
@ -319,7 +332,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
/*
|
||||
* Process servo mix table UI
|
||||
*/
|
||||
let rules = SERVO_RULES.get();
|
||||
let rules = FC.SERVO_RULES.get();
|
||||
$servoMixTableBody.find("*").remove();
|
||||
for (let servoRuleIndex in rules) {
|
||||
if (rules.hasOwnProperty(servoRuleIndex)) {
|
||||
|
@ -341,7 +354,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
|
||||
GUI.renderLogicConditionSelect(
|
||||
$row.find('.mixer-table__condition'),
|
||||
LOGIC_CONDITIONS,
|
||||
FC.LOGIC_CONDITIONS,
|
||||
servoRule.getConditionId(),
|
||||
function () {
|
||||
servoRule.setConditionId($(this).val());
|
||||
|
@ -352,7 +365,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
|
||||
GUI.fillSelect($row.find(".mix-rule-input"), FC.getServoMixInputNames(), servoRule.getInput());
|
||||
|
||||
if (!MIXER_CONFIG.hasFlaps) {
|
||||
if (!FC.MIXER_CONFIG.hasFlaps) {
|
||||
$row.find(".mix-rule-input").children('option[value="14"]').remove();
|
||||
}
|
||||
|
||||
|
@ -404,7 +417,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
|
||||
// Show the Fixed Value column if at least one servo has the "MAX" input assigned
|
||||
const $fixedValueCol = $("#servo-mix-table").find(".mixer-fixed-value-col");
|
||||
const rules = SERVO_RULES.get();
|
||||
const rules = FC.SERVO_RULES.get();
|
||||
for (let servoRuleIndex in rules) {
|
||||
if (rules.hasOwnProperty(servoRuleIndex)) {
|
||||
if (FC.getServoMixInputNames()[rules[servoRuleIndex].getInput()] === 'MAX') {
|
||||
|
@ -427,7 +440,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
var rules;
|
||||
|
||||
if (currentMixerPreset.id == loadedMixerPresetID) {
|
||||
rules = MOTOR_RULES.get();
|
||||
rules = FC.MOTOR_RULES.get();
|
||||
} else {
|
||||
rules = currentMixerPreset.motorMixer;
|
||||
}
|
||||
|
@ -463,7 +476,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
/*
|
||||
* Process motor mix table UI
|
||||
*/
|
||||
var rules = MOTOR_RULES.get();
|
||||
var rules = FC.MOTOR_RULES.get();
|
||||
$motorMixTableBody.find("*").remove();
|
||||
let index = 0;
|
||||
for (const i in rules) {
|
||||
|
@ -529,10 +542,10 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
/*
|
||||
* Send mixer rules
|
||||
*/
|
||||
SERVO_RULES.cleanup();
|
||||
SERVO_RULES.inflate();
|
||||
MOTOR_RULES.cleanup();
|
||||
MOTOR_RULES.inflate();
|
||||
FC.SERVO_RULES.cleanup();
|
||||
FC.SERVO_RULES.inflate();
|
||||
FC.MOTOR_RULES.cleanup();
|
||||
FC.MOTOR_RULES.inflate();
|
||||
|
||||
updateTimerOverride();
|
||||
|
||||
|
@ -547,7 +560,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
$motorMixTableBody = $motorMixTable.find('tbody');
|
||||
|
||||
function fillMixerPreset() {
|
||||
let mixers = helper.mixer.getByPlatform(MIXER_CONFIG.platformType);
|
||||
let mixers = mixer.getByPlatform(FC.MIXER_CONFIG.platformType);
|
||||
|
||||
$mixerPreset.find("*").remove();
|
||||
for (let i in mixers) {
|
||||
|
@ -559,7 +572,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
let $platformSelect = $('#platform-type'),
|
||||
platforms = helper.platform.getList(),
|
||||
platforms = platform.getList(),
|
||||
$mixerPreset = $('#mixer-preset'),
|
||||
$wizardButton = $("#mixer-wizard");
|
||||
|
||||
|
@ -600,7 +613,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
return;
|
||||
}
|
||||
|
||||
MOTOR_RULES.flush();
|
||||
FC.MOTOR_RULES.flush();
|
||||
|
||||
for (let i = 0; i < 4; i++) {
|
||||
const $selects = $(".wizard-motor-select");
|
||||
|
@ -614,7 +627,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
|
||||
const r = currentMixerPreset.motorMixer[rule];
|
||||
|
||||
MOTOR_RULES.put(
|
||||
FC.MOTOR_RULES.put(
|
||||
new MotorMixRule(
|
||||
r.getThrottle(),
|
||||
r.getRoll(),
|
||||
|
@ -633,13 +646,13 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
|
||||
const updateMotorDirection = function () {
|
||||
let motorDirectionCheckbox = $("#motor_direction_inverted");
|
||||
const isReversed = motorDirectionCheckbox.is(":checked") && (MIXER_CONFIG.platformType == PLATFORM.MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM.TRICOPTER);
|
||||
const isReversed = motorDirectionCheckbox.is(":checked") && (FC.MIXER_CONFIG.platformType == PLATFORM.MULTIROTOR || FC.MIXER_CONFIG.platformType == PLATFORM.TRICOPTER);
|
||||
|
||||
const path = './resources/motor_order/'
|
||||
+ currentMixerPreset.image + (isReversed ? "_reverse" : "") + '.svg';
|
||||
$('.mixerPreview img').attr('src', path);
|
||||
|
||||
if (MIXER_CONFIG.platformType == PLATFORM.MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM.TRICOPTER) {
|
||||
if (FC.MIXER_CONFIG.platformType == PLATFORM.MULTIROTOR || FC.MIXER_CONFIG.platformType == PLATFORM.TRICOPTER) {
|
||||
if (isReversed) {
|
||||
motorDirectionCheckbox.parent().find("label span").html(i18n.getMessage("motor_direction_isInverted"));
|
||||
} else {
|
||||
|
@ -662,8 +675,8 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
$platformSelect.on('change', function () {
|
||||
MIXER_CONFIG.platformType = parseInt($platformSelect.val(), 10);
|
||||
currentPlatform = helper.platform.getById(MIXER_CONFIG.platformType);
|
||||
FC.MIXER_CONFIG.platformType = parseInt($platformSelect.val(), 10);
|
||||
currentPlatform = platform.getById(FC.MIXER_CONFIG.platformType);
|
||||
|
||||
var $platformSelectParent = $platformSelect.parent('.select');
|
||||
|
||||
|
@ -671,14 +684,14 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
$mixerPreset.trigger('change');
|
||||
});
|
||||
|
||||
currentPlatform = helper.platform.getById(MIXER_CONFIG.platformType);
|
||||
$platformSelect.val(MIXER_CONFIG.platformType).trigger('change');
|
||||
currentPlatform = platform.getById(FC.MIXER_CONFIG.platformType);
|
||||
$platformSelect.val(FC.MIXER_CONFIG.platformType).trigger('change');
|
||||
|
||||
$mixerPreset.on('change', function () {
|
||||
const presetId = parseInt($mixerPreset.val(), 10);
|
||||
currentMixerPreset = helper.mixer.getById(presetId);
|
||||
currentMixerPreset = mixer.getById(presetId);
|
||||
|
||||
MIXER_CONFIG.appliedMixerPreset = presetId;
|
||||
FC.MIXER_CONFIG.appliedMixerPreset = presetId;
|
||||
|
||||
if (currentMixerPreset.id == 3) {
|
||||
$wizardButton.parent().removeClass("is-hidden");
|
||||
|
@ -686,13 +699,13 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
$wizardButton.parent().addClass("is-hidden");
|
||||
}
|
||||
|
||||
if (MIXER_CONFIG.platformType == PLATFORM.AIRPLANE && currentMixerPreset.id != loadedMixerPresetID) {
|
||||
if (FC.MIXER_CONFIG.platformType == PLATFORM.AIRPLANE && currentMixerPreset.id != loadedMixerPresetID) {
|
||||
$("#needToUpdateMixerMessage").removeClass("is-hidden");
|
||||
} else {
|
||||
$("#needToUpdateMixerMessage").addClass("is-hidden");
|
||||
}
|
||||
|
||||
if (MIXER_CONFIG.platformType == PLATFORM.MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM.TRICOPTER) {
|
||||
if (FC.MIXER_CONFIG.platformType == PLATFORM.MULTIROTOR || FC.MIXER_CONFIG.platformType == PLATFORM.TRICOPTER) {
|
||||
$('#motor_direction_inverted').parent().removeClass("is-hidden");
|
||||
$('#platform-type').parent('.select').removeClass('no-bottom-border');
|
||||
} else {
|
||||
|
@ -701,7 +714,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
if (!GUI.updateEzTuneTabVisibility(false)) {
|
||||
EZ_TUNE.enabled = 0;
|
||||
FC.EZ_TUNE.enabled = 0;
|
||||
mspHelper.saveEzTune();
|
||||
}
|
||||
|
||||
|
@ -710,10 +723,10 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
updateMotorDirection();
|
||||
});
|
||||
|
||||
if (MIXER_CONFIG.appliedMixerPreset > -1) {
|
||||
loadedMixerPresetID = MIXER_CONFIG.appliedMixerPreset;
|
||||
if (FC.MIXER_CONFIG.appliedMixerPreset > -1) {
|
||||
loadedMixerPresetID = FC.MIXER_CONFIG.appliedMixerPreset;
|
||||
$("#needToUpdateMixerMessage").addClass("is-hidden");
|
||||
$mixerPreset.val(MIXER_CONFIG.appliedMixerPreset).trigger('change');
|
||||
$mixerPreset.val(FC.MIXER_CONFIG.appliedMixerPreset).trigger('change');
|
||||
} else {
|
||||
$mixerPreset.trigger('change');
|
||||
}
|
||||
|
@ -730,9 +743,9 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
|
||||
$('#execute-button').on('click', function () {
|
||||
loadedMixerPresetID = currentMixerPreset.id;
|
||||
helper.mixer.loadServoRules(currentMixerPreset);
|
||||
helper.mixer.loadMotorRules(currentMixerPreset);
|
||||
MIXER_CONFIG.hasFlaps = (currentMixerPreset.hasFlaps === true) ? true : false;
|
||||
mixer.loadServoRules(currentMixerPreset);
|
||||
mixer.loadMotorRules(currentMixerPreset);
|
||||
FC.MIXER_CONFIG.hasFlaps = (currentMixerPreset.hasFlaps === true) ? true : false;
|
||||
renderServoMixRules();
|
||||
renderMotorMixRules();
|
||||
renderOutputMapping();
|
||||
|
@ -741,13 +754,13 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
});
|
||||
|
||||
$('#load-mixer-button').on('click', function () {
|
||||
if (MIXER_CONFIG.platformType == PLATFORM.AIRPLANE) {
|
||||
if (FC.MIXER_CONFIG.platformType == PLATFORM.AIRPLANE) {
|
||||
$("#needToUpdateMixerMessage").addClass("is-hidden");
|
||||
}
|
||||
loadedMixerPresetID = currentMixerPreset.id;
|
||||
helper.mixer.loadServoRules(currentMixerPreset);
|
||||
helper.mixer.loadMotorRules(currentMixerPreset);
|
||||
MIXER_CONFIG.hasFlaps = (currentMixerPreset.hasFlaps === true) ? true : false;
|
||||
mixer.loadServoRules(currentMixerPreset);
|
||||
mixer.loadMotorRules(currentMixerPreset);
|
||||
FC.MIXER_CONFIG.hasFlaps = (currentMixerPreset.hasFlaps === true) ? true : false;
|
||||
renderServoMixRules();
|
||||
renderMotorMixRules();
|
||||
renderOutputMapping();
|
||||
|
@ -755,10 +768,10 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
});
|
||||
|
||||
$('#refresh-mixer-button').on('click', function () {
|
||||
currentMixerPreset = helper.mixer.getById(loadedMixerPresetID);
|
||||
MIXER_CONFIG.platformType = currentMixerPreset.platform;
|
||||
currentPlatform = helper.platform.getById(MIXER_CONFIG.platformType);
|
||||
$platformSelect.val(MIXER_CONFIG.platformType).trigger('change');
|
||||
currentMixerPreset = mixer.getById(loadedMixerPresetID);
|
||||
FC.MIXER_CONFIG.platformType = currentMixerPreset.platform;
|
||||
currentPlatform = platform.getById(FC.MIXER_CONFIG.platformType);
|
||||
$platformSelect.val(FC.MIXER_CONFIG.platformType).trigger('change');
|
||||
$mixerPreset.val(loadedMixerPresetID).trigger('change');
|
||||
renderServoMixRules();
|
||||
renderMotorMixRules();
|
||||
|
@ -766,13 +779,13 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
});
|
||||
|
||||
$servoMixTableBody.on('click', "[data-role='role-servo-delete']", function (event) {
|
||||
SERVO_RULES.drop($(event.currentTarget).attr("data-index"));
|
||||
FC.SERVO_RULES.drop($(event.currentTarget).attr("data-index"));
|
||||
renderServoMixRules();
|
||||
renderOutputMapping();
|
||||
});
|
||||
|
||||
$motorMixTableBody.on('click', "[data-role='role-motor-delete']", function (event) {
|
||||
MOTOR_RULES.drop($(event.currentTarget).attr("data-index"));
|
||||
FC.MOTOR_RULES.drop($(event.currentTarget).attr("data-index"));
|
||||
renderMotorMixRules();
|
||||
renderOutputMapping();
|
||||
});
|
||||
|
@ -782,23 +795,23 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
});
|
||||
|
||||
$("[data-role='role-servo-add']").on('click', function () {
|
||||
if (SERVO_RULES.hasFreeSlots()) {
|
||||
SERVO_RULES.put(new ServoMixRule(SERVO_RULES.getNextUnusedIndex(), 0, 100, 0));
|
||||
if (FC.SERVO_RULES.hasFreeSlots()) {
|
||||
FC.SERVO_RULES.put(new ServoMixRule(FC.SERVO_RULES.getNextUnusedIndex(), 0, 100, 0));
|
||||
renderServoMixRules();
|
||||
renderOutputMapping();
|
||||
}
|
||||
});
|
||||
|
||||
$("[data-role='role-motor-add']").on('click', function () {
|
||||
if (MOTOR_RULES.hasFreeSlots()) {
|
||||
MOTOR_RULES.put(new MotorMixRule(1, 0, 0, 0));
|
||||
if (FC.MOTOR_RULES.hasFreeSlots()) {
|
||||
FC.MOTOR_RULES.put(new MotorMixRule(1, 0, 0, 0));
|
||||
renderMotorMixRules();
|
||||
renderOutputMapping();
|
||||
}
|
||||
});
|
||||
|
||||
$("[data-role='role-logic-conditions-open']").on('click', function () {
|
||||
LOGIC_CONDITIONS.open();
|
||||
FC.LOGIC_CONDITIONS.open();
|
||||
});
|
||||
|
||||
$('#save-button').on('click', saveAndReboot);
|
||||
|
@ -810,11 +823,11 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
renderOutputMapping();
|
||||
renderTimerOverride();
|
||||
|
||||
LOGIC_CONDITIONS.init($('#logic-wrapper'));
|
||||
FC.LOGIC_CONDITIONS.init($('#logic-wrapper'));
|
||||
|
||||
i18n.localize();;
|
||||
|
||||
helper.mspBalancedInterval.add('logic_conditions_pull', 350, 1, getLogicConditionsStatus);
|
||||
mspBalancedInterval.add('logic_conditions_pull', 350, 1, getLogicConditionsStatus);
|
||||
|
||||
GUI.content_ready(callback);
|
||||
}
|
||||
|
@ -835,7 +848,7 @@ TABS.mixer.initialize = function (callback, scrollPosition) {
|
|||
}
|
||||
|
||||
function onStatusPullDone() {
|
||||
LOGIC_CONDITIONS.update(LOGIC_CONDITIONS_STATUS);
|
||||
FC.LOGIC_CONDITIONS.update(FC.LOGIC_CONDITIONS_STATUS);
|
||||
}
|
||||
|
||||
};
|
||||
|
|
209
tabs/outputs.js
209
tabs/outputs.js
|
@ -1,6 +1,23 @@
|
|||
/*global helper,MSP,MSPChainerClass,GUI,mspHelper,MOTOR_RULES,TABS,$,MSPCodes,ANALOG,MOTOR_DATA,chrome,PLATFORM.MULTIROTOR,PLATFORM.TRICOPTER,SERVO_RULES,FC,SERVO_CONFIG,SENSOR_DATA,REVERSIBLE_MOTORS,MISC,MIXER_CONFIG,OUTPUT_MAPPING*/
|
||||
'use strict';
|
||||
|
||||
const path = require('path');
|
||||
|
||||
const MSPChainerClass = require('./../js/msp/MSPchainer');
|
||||
const mspHelper = require('./../js/msp/MSPHelper');
|
||||
const MSPCodes = require('./../js/msp/MSPCodes');
|
||||
const mspBalancedInterval = require('./../js/msp_balanced_interval.js');
|
||||
const mspQueue = require('./../js/serial_queue.js')
|
||||
const MSP = require('./../js/msp');
|
||||
const { GUI, TABS } = require('./../js/gui');
|
||||
const FC = require('./../js/fc');
|
||||
const i18n = require('./../js/localization');
|
||||
const BitHelper = require('../js/bitHelper');
|
||||
const Settings = require('./../js/settings.js');
|
||||
const features = require('./../js/feature_framework.js');
|
||||
const { mixer, PLATFORM } = require('./../js/model');
|
||||
const timeout = require('./../js/timeouts.js')
|
||||
const interval = require('./../js/intervals.js');
|
||||
|
||||
TABS.outputs = {
|
||||
allowTestMode: false,
|
||||
feature3DEnabled: false,
|
||||
|
@ -56,11 +73,11 @@ TABS.outputs.initialize = function (callback) {
|
|||
]);
|
||||
saveChainer.setExitPoint(function () {
|
||||
GUI.log(i18n.getMessage('eeprom_saved_ok'));
|
||||
MOTOR_RULES.cleanup();
|
||||
FC.MOTOR_RULES.cleanup();
|
||||
});
|
||||
|
||||
function load_html() {
|
||||
GUI.load(path.join(__dirname, "tabs/outputs.html"), Settings.processHtml(onLoad));
|
||||
GUI.load(path.join(__dirname, "outputs.html"), Settings.processHtml(onLoad));
|
||||
}
|
||||
|
||||
function saveSettings(onComplete) {
|
||||
|
@ -69,7 +86,7 @@ TABS.outputs.initialize = function (callback) {
|
|||
|
||||
function onLoad() {
|
||||
|
||||
self.feature3DEnabled = bit_check(FEATURES, 12);
|
||||
self.feature3DEnabled = BitHelper.bit_check(FC.FEATURES, 12);
|
||||
|
||||
process_motors();
|
||||
process_servos();
|
||||
|
@ -81,8 +98,8 @@ TABS.outputs.initialize = function (callback) {
|
|||
function getMotorOutputValue(value) {
|
||||
|
||||
if (!self.feature3DEnabled) {
|
||||
let valueNormalized = value - MISC.mincommand;
|
||||
let maxThrottleNormalized = MISC.maxthrottle - MISC.mincommand;
|
||||
let valueNormalized = value - FC.MISC.mincommand;
|
||||
let maxThrottleNormalized = FC.MISC.maxthrottle - FC.MISC.mincommand;
|
||||
|
||||
return Math.round(100 * valueNormalized / maxThrottleNormalized) + "%";
|
||||
} else {
|
||||
|
@ -100,7 +117,7 @@ TABS.outputs.initialize = function (callback) {
|
|||
|
||||
function handleIdleMessageBox() {
|
||||
$idleInfoBox.hide();
|
||||
if (ADVANCED_CONFIG.motorPwmProtocol >= 5) {
|
||||
if (FC.ADVANCED_CONFIG.motorPwmProtocol >= 5) {
|
||||
$('.hide-for-shot').hide();
|
||||
if ($idlePercent.val() > 7.0) {
|
||||
$idleInfoBox.html(i18n.getMessage('throttleIdleDigitalInfo'));
|
||||
|
@ -126,10 +143,10 @@ TABS.outputs.initialize = function (callback) {
|
|||
}
|
||||
}
|
||||
|
||||
$escProtocol.val(ADVANCED_CONFIG.motorPwmProtocol);
|
||||
$escProtocol.val(FC.ADVANCED_CONFIG.motorPwmProtocol);
|
||||
|
||||
$escProtocol.on('change', function () {
|
||||
ADVANCED_CONFIG.motorPwmProtocol = $(this).val();
|
||||
FC.ADVANCED_CONFIG.motorPwmProtocol = $(this).val();
|
||||
});
|
||||
|
||||
$idlePercent.on('change', handleIdleMessageBox);
|
||||
|
@ -147,18 +164,18 @@ TABS.outputs.initialize = function (callback) {
|
|||
/*
|
||||
* If rate from FC is not on the list, add a new entry
|
||||
*/
|
||||
if ($servoRate.find('[value="' + ADVANCED_CONFIG.servoPwmRate + '"]').length == 0) {
|
||||
$servoRate.append('<option value="' + ADVANCED_CONFIG.servoPwmRate + '">' + ADVANCED_CONFIG.servoPwmRate + 'Hz</option>');
|
||||
if ($servoRate.find('[value="' + FC.ADVANCED_CONFIG.servoPwmRate + '"]').length == 0) {
|
||||
$servoRate.append('<option value="' + FC.ADVANCED_CONFIG.servoPwmRate + '">' + FC.ADVANCED_CONFIG.servoPwmRate + 'Hz</option>');
|
||||
}
|
||||
|
||||
$servoRate.val(ADVANCED_CONFIG.servoPwmRate);
|
||||
$servoRate.val(FC.ADVANCED_CONFIG.servoPwmRate);
|
||||
$servoRate.on('change', function () {
|
||||
ADVANCED_CONFIG.servoPwmRate = $(this).val();
|
||||
FC.ADVANCED_CONFIG.servoPwmRate = $(this).val();
|
||||
});
|
||||
|
||||
$('#servo-rate-container').show();
|
||||
|
||||
helper.features.updateUI($('.tab-motors'), FEATURES);
|
||||
features.updateUI($('.tab-motors'), FC.FEATURES);
|
||||
GUI.simpleBind();
|
||||
|
||||
let $reversibleMotorCheckbox = $('#feature-12');
|
||||
|
@ -178,7 +195,7 @@ TABS.outputs.initialize = function (callback) {
|
|||
|
||||
let $motorStopCheckbox = $('#feature-4');
|
||||
function showHideMotorStopWarning() {
|
||||
const platformNeedsMotorStop = [PLATFORM.AIRPLANE, PLATFORM.ROVER, PLATFORM.BOAT].includes(MIXER_CONFIG.platformType);
|
||||
const platformNeedsMotorStop = [PLATFORM.AIRPLANE, PLATFORM.ROVER, PLATFORM.BOAT].includes(FC.MIXER_CONFIG.platformType);
|
||||
const motorStopEnabled = $motorStopCheckbox.is(':checked');
|
||||
if (platformNeedsMotorStop && motorStopEnabled || !platformNeedsMotorStop && !motorStopEnabled) {
|
||||
$motorStopWarningBox.hide();
|
||||
|
@ -189,9 +206,9 @@ TABS.outputs.initialize = function (callback) {
|
|||
$motorStopCheckbox.on('change', showHideMotorStopWarning);
|
||||
showHideMotorStopWarning();
|
||||
|
||||
$('#3ddeadbandlow').val(REVERSIBLE_MOTORS.deadband_low);
|
||||
$('#3ddeadbandhigh').val(REVERSIBLE_MOTORS.deadband_high);
|
||||
$('#3dneutral').val(REVERSIBLE_MOTORS.neutral);
|
||||
$('#3ddeadbandlow').val(FC.REVERSIBLE_MOTORS.deadband_low);
|
||||
$('#3ddeadbandhigh').val(FC.REVERSIBLE_MOTORS.deadband_high);
|
||||
$('#3dneutral').val(FC.REVERSIBLE_MOTORS.neutral);
|
||||
}
|
||||
|
||||
function update_arm_status() {
|
||||
|
@ -200,7 +217,7 @@ TABS.outputs.initialize = function (callback) {
|
|||
|
||||
function initSensorData() {
|
||||
for (var i = 0; i < 3; i++) {
|
||||
SENSOR_DATA.accelerometer[i] = 0;
|
||||
FC.SENSOR_DATA.accelerometer[i] = 0;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -234,13 +251,13 @@ TABS.outputs.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function update_model(val) {
|
||||
if (MIXER_CONFIG.appliedMixerPreset == -1) return;
|
||||
if (FC.MIXER_CONFIG.appliedMixerPreset == -1) return;
|
||||
|
||||
const isMotorInverted = self.motorDirectionInverted;
|
||||
const isReversed = isMotorInverted && (MIXER_CONFIG.platformType == PLATFORM.MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM.TRICOPTER);
|
||||
const isReversed = isMotorInverted && (FC.MIXER_CONFIG.platformType == PLATFORM.MULTIROTOR || FC.MIXER_CONFIG.platformType == PLATFORM.TRICOPTER);
|
||||
|
||||
const path = './resources/motor_order/'
|
||||
+ helper.mixer.getById(val).image + (isReversed ? "_reverse" : "") + '.svg';
|
||||
+ mixer.getById(val).image + (isReversed ? "_reverse" : "") + '.svg';
|
||||
$('.mixerPreview img').attr('src', path);
|
||||
}
|
||||
|
||||
|
@ -251,7 +268,7 @@ TABS.outputs.initialize = function (callback) {
|
|||
$servoConfigTableContainer = $('#servo-config-table-container'),
|
||||
$servoConfigTable = $('#servo-config-table');
|
||||
|
||||
if (SERVO_CONFIG.length == 0) {
|
||||
if (FC.SERVO_CONFIG.length == 0) {
|
||||
$tabServos.addClass("is-hidden");
|
||||
return;
|
||||
}
|
||||
|
@ -261,9 +278,9 @@ TABS.outputs.initialize = function (callback) {
|
|||
$servoConfigTable.append('\
|
||||
<tr> \
|
||||
<td class="text-center">' + name + '</td>\
|
||||
<td class="middle"><input type="number" min="500" max="2500" value="' + SERVO_CONFIG[obj].middle + '" /></td>\
|
||||
<td class="min"><input type="number" min="500" max="2500" value="' + SERVO_CONFIG[obj].min + '" /></td>\
|
||||
<td class="max"><input type="number" min="500" max="2500" value="' + SERVO_CONFIG[obj].max + '" /></td>\
|
||||
<td class="middle"><input type="number" min="500" max="2500" value="' + FC.SERVO_CONFIG[obj].middle + '" /></td>\
|
||||
<td class="min"><input type="number" min="500" max="2500" value="' + FC.SERVO_CONFIG[obj].min + '" /></td>\
|
||||
<td class="max"><input type="number" min="500" max="2500" value="' + FC.SERVO_CONFIG[obj].max + '" /></td>\
|
||||
<td class="text-center rate">\
|
||||
<td class="text-center reverse">\
|
||||
</td>\
|
||||
|
@ -273,17 +290,17 @@ TABS.outputs.initialize = function (callback) {
|
|||
let $currentRow = $servoConfigTable.find('tr:last');
|
||||
|
||||
//This routine is pre 2.0 only
|
||||
if (SERVO_CONFIG[obj].indexOfChannelToForward >= 0) {
|
||||
$currentRow.find('td.channel input').eq(SERVO_CONFIG[obj].indexOfChannelToForward).prop('checked', true);
|
||||
if (FC.SERVO_CONFIG[obj].indexOfChannelToForward >= 0) {
|
||||
$currentRow.find('td.channel input').eq(FC.SERVO_CONFIG[obj].indexOfChannelToForward).prop('checked', true);
|
||||
}
|
||||
|
||||
// adding select box and generating options
|
||||
$currentRow.find('td.rate').append(
|
||||
'<input class="rate-input" type="number" min="' + FC.MIN_SERVO_RATE + '" max="' + FC.MAX_SERVO_RATE + '" value="' + Math.abs(SERVO_CONFIG[obj].rate) + '" />'
|
||||
'<input class="rate-input" type="number" min="' + FC.MIN_SERVO_RATE + '" max="' + FC.MAX_SERVO_RATE + '" value="' + Math.abs(FC.SERVO_CONFIG[obj].rate) + '" />'
|
||||
);
|
||||
|
||||
$currentRow.find('td.reverse').append(
|
||||
'<input type="checkbox" class="reverse-input togglemedium" ' + (SERVO_CONFIG[obj].rate < 0 ? ' checked ' : '') + '/>'
|
||||
'<input type="checkbox" class="reverse-input togglemedium" ' + (FC.SERVO_CONFIG[obj].rate < 0 ? ' checked ' : '') + '/>'
|
||||
);
|
||||
|
||||
$currentRow.data('info', { 'obj': obj });
|
||||
|
@ -293,10 +310,10 @@ TABS.outputs.initialize = function (callback) {
|
|||
let output,
|
||||
outputString;
|
||||
|
||||
if (MIXER_CONFIG.platformType == PLATFORM.MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM.TRICOPTER) {
|
||||
output = OUTPUT_MAPPING.getMrServoOutput(usedServoIndex);
|
||||
if (FC.MIXER_CONFIG.platformType == PLATFORM.MULTIROTOR || FC.MIXER_CONFIG.platformType == PLATFORM.TRICOPTER) {
|
||||
output = FC.OUTPUT_MAPPING.getMrServoOutput(usedServoIndex);
|
||||
} else {
|
||||
output = OUTPUT_MAPPING.getFwServoOutput(usedServoIndex);
|
||||
output = FC.OUTPUT_MAPPING.getFwServoOutput(usedServoIndex);
|
||||
}
|
||||
|
||||
if (output === null) {
|
||||
|
@ -307,7 +324,7 @@ TABS.outputs.initialize = function (callback) {
|
|||
|
||||
$currentRow.find('.output').html(outputString);
|
||||
//For 2.0 and above hide a row when servo is not configured
|
||||
if (!SERVO_RULES.isServoConfigured(obj)) {
|
||||
if (!FC.SERVO_RULES.isServoConfigured(obj)) {
|
||||
$currentRow.hide();
|
||||
} else {
|
||||
usedServoIndex++;
|
||||
|
@ -324,21 +341,21 @@ TABS.outputs.initialize = function (callback) {
|
|||
channelIndex = undefined;
|
||||
}
|
||||
|
||||
SERVO_CONFIG[info.obj].indexOfChannelToForward = channelIndex;
|
||||
FC.SERVO_CONFIG[info.obj].indexOfChannelToForward = channelIndex;
|
||||
|
||||
SERVO_CONFIG[info.obj].middle = parseInt($('.middle input', this).val());
|
||||
SERVO_CONFIG[info.obj].min = parseInt($('.min input', this).val());
|
||||
SERVO_CONFIG[info.obj].max = parseInt($('.max input', this).val());
|
||||
FC.SERVO_CONFIG[info.obj].middle = parseInt($('.middle input', this).val());
|
||||
FC.SERVO_CONFIG[info.obj].min = parseInt($('.min input', this).val());
|
||||
FC.SERVO_CONFIG[info.obj].max = parseInt($('.max input', this).val());
|
||||
var rate = parseInt($('.rate-input', this).val());
|
||||
if ($('.reverse-input', this).is(':checked')) {
|
||||
rate = -rate;
|
||||
}
|
||||
SERVO_CONFIG[info.obj].rate = rate;
|
||||
FC.SERVO_CONFIG[info.obj].rate = rate;
|
||||
});
|
||||
|
||||
REVERSIBLE_MOTORS.deadband_low = parseInt($('#3ddeadbandlow').val());
|
||||
REVERSIBLE_MOTORS.deadband_high = parseInt($('#3ddeadbandhigh').val());
|
||||
REVERSIBLE_MOTORS.neutral = parseInt($('#3dneutral').val());
|
||||
FC.REVERSIBLE_MOTORS.deadband_low = parseInt($('#3ddeadbandlow').val());
|
||||
FC.REVERSIBLE_MOTORS.deadband_high = parseInt($('#3ddeadbandhigh').val());
|
||||
FC.REVERSIBLE_MOTORS.neutral = parseInt($('#3dneutral').val());
|
||||
|
||||
//Save configuration to FC
|
||||
saveChainer.execute();
|
||||
|
@ -349,7 +366,7 @@ TABS.outputs.initialize = function (callback) {
|
|||
|
||||
let usedServoIndex = 0;
|
||||
|
||||
for (let servoIndex = 0; servoIndex < SERVO_RULES.getServoCount(); servoIndex++) {
|
||||
for (let servoIndex = 0; servoIndex < FC.SERVO_RULES.getServoCount(); servoIndex++) {
|
||||
renderServos('Servo ' + servoIndex, '', servoIndex);
|
||||
}
|
||||
if (usedServoIndex == 0) {
|
||||
|
@ -365,14 +382,14 @@ TABS.outputs.initialize = function (callback) {
|
|||
$('table.directions select, table.directions input, #servo-config-table select, #servo-config-table input').on('change', function () {
|
||||
if ($('div.live input').is(':checked')) {
|
||||
// apply small delay as there seems to be some funky update business going wrong
|
||||
helper.timeout.add('servos_update', servos_update, 10);
|
||||
timeout.add('servos_update', servos_update, 10);
|
||||
}
|
||||
});
|
||||
|
||||
$('a.update').on('click', function () {
|
||||
helper.features.reset();
|
||||
helper.features.fromUI($('.tab-motors'));
|
||||
helper.features.execute(servos_update);
|
||||
features.reset();
|
||||
features.fromUI($('.tab-motors'));
|
||||
features.execute(servos_update);
|
||||
});
|
||||
$('a.save').on('click', function () {
|
||||
saveChainer.setExitPoint(function () {
|
||||
|
@ -386,9 +403,9 @@ TABS.outputs.initialize = function (callback) {
|
|||
});
|
||||
});
|
||||
});
|
||||
helper.features.reset();
|
||||
helper.features.fromUI($('.tab-motors'));
|
||||
helper.features.execute(servos_update);
|
||||
features.reset();
|
||||
features.fromUI($('.tab-motors'));
|
||||
features.execute(servos_update);
|
||||
});
|
||||
|
||||
}
|
||||
|
@ -403,7 +420,7 @@ TABS.outputs.initialize = function (callback) {
|
|||
$motorsEnableTestMode.prop('checked', false);
|
||||
$motorsEnableTestMode.prop('disabled', true);
|
||||
|
||||
update_model(MIXER_CONFIG.appliedMixerPreset);
|
||||
update_model(FC.MIXER_CONFIG.appliedMixerPreset);
|
||||
|
||||
// Always start with default/empty sensor data array, clean slate all
|
||||
initSensorData();
|
||||
|
@ -420,15 +437,15 @@ TABS.outputs.initialize = function (callback) {
|
|||
$voltageHelper = $(".current-voltage");
|
||||
|
||||
// timer initialization
|
||||
helper.interval.killAll(['motor_and_status_pull', 'global_data_refresh', 'msp-load-update']);
|
||||
helper.mspBalancedInterval.flush();
|
||||
interval.killAll(['motor_and_status_pull', 'global_data_refresh', 'msp-load-update']);
|
||||
mspBalancedInterval.flush();
|
||||
|
||||
helper.interval.add('IMU_pull', function () {
|
||||
interval.add('IMU_pull', function () {
|
||||
|
||||
/*
|
||||
* Enable balancer
|
||||
*/
|
||||
if (helper.mspQueue.shouldDrop()) {
|
||||
if (mspQueue.shouldDrop()) {
|
||||
update_accel_graph();
|
||||
return;
|
||||
}
|
||||
|
@ -436,25 +453,25 @@ TABS.outputs.initialize = function (callback) {
|
|||
MSP.send_message(MSPCodes.MSP_RAW_IMU, false, false, update_accel_graph);
|
||||
}, 25, true);
|
||||
|
||||
helper.interval.add('ANALOG_pull', function () {
|
||||
$currentHelper.html(ANALOG.amperage.toFixed(2));
|
||||
$voltageHelper.html(ANALOG.voltage.toFixed(2));
|
||||
interval.add('ANALOG_pull', function () {
|
||||
$currentHelper.html(FC.ANALOG.amperage.toFixed(2));
|
||||
$voltageHelper.html(FC.ANALOG.voltage.toFixed(2));
|
||||
}, 100, true);
|
||||
|
||||
function update_accel_graph() {
|
||||
|
||||
if (!accel_offset_established) {
|
||||
for (var i = 0; i < 3; i++) {
|
||||
accel_offset[i] = SENSOR_DATA.accelerometer[i] * -1;
|
||||
accel_offset[i] = FC.SENSOR_DATA.accelerometer[i] * -1;
|
||||
}
|
||||
|
||||
accel_offset_established = true;
|
||||
}
|
||||
|
||||
var accel_with_offset = [
|
||||
accel_offset[0] + SENSOR_DATA.accelerometer[0],
|
||||
accel_offset[1] + SENSOR_DATA.accelerometer[1],
|
||||
accel_offset[2] + SENSOR_DATA.accelerometer[2]
|
||||
accel_offset[0] + FC.SENSOR_DATA.accelerometer[0],
|
||||
accel_offset[1] + FC.SENSOR_DATA.accelerometer[1],
|
||||
accel_offset[2] + FC.SENSOR_DATA.accelerometer[2]
|
||||
];
|
||||
|
||||
samples_accel_i = addSampleToData(accel_data, samples_accel_i, accel_with_offset);
|
||||
|
@ -481,7 +498,7 @@ TABS.outputs.initialize = function (callback) {
|
|||
$motorSliders = $('.motor-sliders'),
|
||||
$motorValues = $('.motor-values');
|
||||
|
||||
for (let i = 0; i < MOTOR_RULES.getNumberOfConfiguredMotors(); i++) {
|
||||
for (let i = 0; i < FC.MOTOR_RULES.getNumberOfConfiguredMotors(); i++) {
|
||||
const motorNumber = i + 1;
|
||||
motors_wrapper.append('\
|
||||
<div class="m-block motor-' + i + '">\
|
||||
|
@ -503,10 +520,10 @@ TABS.outputs.initialize = function (callback) {
|
|||
$motorSliders.append('<div class="motor-slider-container"><input type="range" min="1000" max="2000" value="1000" disabled="disabled" class="master"/></div>');
|
||||
$motorValues.append('<li style="font-weight: bold" data-i18n="motorsMaster"></li>');
|
||||
|
||||
for (let i = 0; i < SERVO_RULES.getServoCount(); i++) {
|
||||
for (let i = 0; i < FC.SERVO_RULES.getServoCount(); i++) {
|
||||
|
||||
let opacity = "";
|
||||
if (!SERVO_RULES.isServoConfigured(15 - i)) {
|
||||
if (!FC.SERVO_RULES.isServoConfigured(15 - i)) {
|
||||
opacity = ' style="opacity: 0.2"';
|
||||
}
|
||||
|
||||
|
@ -526,19 +543,19 @@ TABS.outputs.initialize = function (callback) {
|
|||
|
||||
var $slidersInput = $('div.sliders input');
|
||||
|
||||
$slidersInput.prop('min', MISC.mincommand);
|
||||
$slidersInput.prop('max', MISC.maxthrottle);
|
||||
$('div.values li:not(:last)').text(MISC.mincommand);
|
||||
$slidersInput.prop('min', FC.MISC.mincommand);
|
||||
$slidersInput.prop('max', FC.MISC.maxthrottle);
|
||||
$('div.values li:not(:last)').text(FC.MISC.mincommand);
|
||||
|
||||
if (self.feature3DEnabled && self.feature3DSupported) {
|
||||
//Arbitrary sanity checks
|
||||
//Note: values may need to be revisited
|
||||
if (REVERSIBLE_MOTORS.neutral > 1575 || REVERSIBLE_MOTORS.neutral < 1425)
|
||||
REVERSIBLE_MOTORS.neutral = 1500;
|
||||
if (FC.REVERSIBLE_MOTORS.neutral > 1575 || FC.EVERSIBLE_MOTORS.neutral < 1425)
|
||||
FC.REVERSIBLE_MOTORS.neutral = 1500;
|
||||
|
||||
$slidersInput.val(REVERSIBLE_MOTORS.neutral);
|
||||
$slidersInput.val(FC.REVERSIBLE_MOTORS.neutral);
|
||||
} else {
|
||||
$slidersInput.val(MISC.mincommand);
|
||||
$slidersInput.val(FC.MISC.mincommand);
|
||||
}
|
||||
|
||||
if (self.allowTestMode) {
|
||||
|
@ -557,8 +574,8 @@ TABS.outputs.initialize = function (callback) {
|
|||
for (let i = 0; i < 8; i++) {
|
||||
var val = parseInt($('div.sliders input').eq(i).val());
|
||||
|
||||
buffer.push(lowByte(val));
|
||||
buffer.push(highByte(val));
|
||||
buffer.push(BitHelper.lowByte(val));
|
||||
buffer.push(BitHelper.highByte(val));
|
||||
}
|
||||
|
||||
buffering_set_motor.push(buffer);
|
||||
|
@ -579,13 +596,13 @@ TABS.outputs.initialize = function (callback) {
|
|||
$('div.sliders input.master').on('input', function () {
|
||||
var val = $(this).val();
|
||||
$('div.sliders input:not(:disabled, :last)').val(val);
|
||||
$('div.values li:not(:last)').slice(0, MOTOR_RULES.getNumberOfConfiguredMotors()).text(getMotorOutputValue(val));
|
||||
$('div.values li:not(:last)').slice(0, FC.MOTOR_RULES.getNumberOfConfiguredMotors()).text(getMotorOutputValue(val));
|
||||
$('div.sliders input:not(:last):first').trigger('input');
|
||||
});
|
||||
|
||||
$motorsEnableTestMode.on('change', function () {
|
||||
if ($(this).is(':checked')) {
|
||||
$slidersInput.slice(0, MOTOR_RULES.getNumberOfConfiguredMotors()).prop('disabled', false);
|
||||
$slidersInput.slice(0, FC.MOTOR_RULES.getNumberOfConfiguredMotors()).prop('disabled', false);
|
||||
|
||||
// unlock master slider
|
||||
$('div.sliders input:last').prop('disabled', false);
|
||||
|
@ -595,9 +612,9 @@ TABS.outputs.initialize = function (callback) {
|
|||
|
||||
// change all values to default
|
||||
if (self.feature3DEnabled && self.feature3DSupported) {
|
||||
$slidersInput.val(REVERSIBLE_MOTORS.neutral);
|
||||
$slidersInput.val(FC.REVERSIBLE_MOTORS.neutral);
|
||||
} else {
|
||||
$slidersInput.val(MISC.mincommand);
|
||||
$slidersInput.val(FC.MISC.mincommand);
|
||||
}
|
||||
|
||||
$slidersInput.trigger('input');
|
||||
|
@ -607,14 +624,14 @@ TABS.outputs.initialize = function (callback) {
|
|||
// check if motors are already spinning
|
||||
var motors_running = false;
|
||||
|
||||
for (var i = 0; i < MOTOR_RULES.getNumberOfConfiguredMotors(); i++) {
|
||||
for (var i = 0; i < FC.MOTOR_RULES.getNumberOfConfiguredMotors(); i++) {
|
||||
if (!self.feature3DEnabled) {
|
||||
if (MOTOR_DATA[i] > MISC.mincommand) {
|
||||
if (FC.MOTOR_DATA[i] > FC.MISC.mincommand) {
|
||||
motors_running = true;
|
||||
break;
|
||||
}
|
||||
} else {
|
||||
if ((MOTOR_DATA[i] < REVERSIBLE_MOTORS.deadband_low) || (MOTOR_DATA[i] > REVERSIBLE_MOTORS.deadband_high)) {
|
||||
if ((FC.MOTOR_DATA[i] < FC.REVERSIBLE_MOTORS.deadband_low) || (FC.MOTOR_DATA[i] > FC.REVERSIBLE_MOTORS.deadband_high)) {
|
||||
motors_running = true;
|
||||
break;
|
||||
}
|
||||
|
@ -629,12 +646,12 @@ TABS.outputs.initialize = function (callback) {
|
|||
|
||||
var sliders = $('div.sliders input:not(.master)');
|
||||
|
||||
var master_value = MOTOR_DATA[0];
|
||||
for (var i = 0; i < MOTOR_DATA.length; i++) {
|
||||
if (MOTOR_DATA[i] > 0) {
|
||||
sliders.eq(i).val(MOTOR_DATA[i]);
|
||||
var master_value = FC.MOTOR_DATA[0];
|
||||
for (var i = 0; i < FC.MOTOR_DATA.length; i++) {
|
||||
if (FC.MOTOR_DATA[i] > 0) {
|
||||
sliders.eq(i).val(FC.MOTOR_DATA[i]);
|
||||
|
||||
if (master_value != MOTOR_DATA[i]) {
|
||||
if (master_value != FC.MOTOR_DATA[i]) {
|
||||
master_value = false;
|
||||
}
|
||||
}
|
||||
|
@ -654,7 +671,7 @@ TABS.outputs.initialize = function (callback) {
|
|||
|
||||
function getPeriodicMotorOutput() {
|
||||
|
||||
if (helper.mspQueue.shouldDrop()) {
|
||||
if (mspQueue.shouldDrop()) {
|
||||
getPeriodicServoOutput();
|
||||
return;
|
||||
}
|
||||
|
@ -663,7 +680,7 @@ TABS.outputs.initialize = function (callback) {
|
|||
}
|
||||
|
||||
function getPeriodicServoOutput() {
|
||||
if (helper.mspQueue.shouldDrop()) {
|
||||
if (mspQueue.shouldDrop()) {
|
||||
update_ui();
|
||||
return;
|
||||
}
|
||||
|
@ -671,7 +688,7 @@ TABS.outputs.initialize = function (callback) {
|
|||
MSP.send_message(MSPCodes.MSP_SERVO, false, false, update_ui);
|
||||
}
|
||||
|
||||
var full_block_scale = MISC.maxthrottle - MISC.mincommand;
|
||||
var full_block_scale = FC.MISC.maxthrottle - FC.MISC.mincommand;
|
||||
|
||||
function update_ui() {
|
||||
var previousArmState = self.armed,
|
||||
|
@ -682,24 +699,24 @@ TABS.outputs.initialize = function (callback) {
|
|||
color,
|
||||
i;
|
||||
|
||||
for (let i= 0; i < MOTOR_DATA.length; i++) {
|
||||
data = MOTOR_DATA[i] - MISC.mincommand;
|
||||
for (let i= 0; i < FC.MOTOR_DATA.length; i++) {
|
||||
data = FC.MOTOR_DATA[i] - FC.MISC.mincommand;
|
||||
margin_top = block_height - (data * (block_height / full_block_scale)).clamp(0, block_height);
|
||||
height = (data * (block_height / full_block_scale)).clamp(0, block_height);
|
||||
color = parseInt(data * 0.009);
|
||||
|
||||
$('.motor-' + i + ' .label', motors_wrapper).text(getMotorOutputValue(MOTOR_DATA[i]));
|
||||
$('.motor-' + i + ' .label', motors_wrapper).text(getMotorOutputValue(FC.MOTOR_DATA[i]));
|
||||
$('.motor-' + i + ' .indicator', motors_wrapper).css({ 'margin-top': margin_top + 'px', 'height': height + 'px', 'background-color': '#37a8db' + color + ')' });
|
||||
}
|
||||
|
||||
// servo indicators are still using old (not flexible block scale), it will be changed in the future accordingly
|
||||
for (let i= 0; i < SERVO_DATA.length; i++) {
|
||||
data = SERVO_DATA[i] - 1000;
|
||||
for (let i= 0; i < FC.SERVO_DATA.length; i++) {
|
||||
data = FC.SERVO_DATA[i] - 1000;
|
||||
margin_top = block_height - (data * (block_height / 1000)).clamp(0, block_height);
|
||||
height = (data * (block_height / 1000)).clamp(0, block_height);
|
||||
color = parseInt(data * 0.009);
|
||||
|
||||
$('.servo-' + i + ' .label', servos_wrapper).text(SERVO_DATA[i]);
|
||||
$('.servo-' + i + ' .label', servos_wrapper).text(FC.SERVO_DATA[i]);
|
||||
$('.servo-' + i + ' .indicator', servos_wrapper).css({ 'margin-top': margin_top + 'px', 'height': height + 'px', 'background-color': '#37a8db' + color + ')' });
|
||||
}
|
||||
//keep the following here so at least we get a visual cue of our motor setup
|
||||
|
@ -722,7 +739,7 @@ TABS.outputs.initialize = function (callback) {
|
|||
}
|
||||
|
||||
// enable Status and Motor data pulling
|
||||
helper.interval.add('motor_and_status_pull', getPeriodicMotorOutput, 100, true);
|
||||
interval.add('motor_and_status_pull', getPeriodicMotorOutput, 100, true);
|
||||
}
|
||||
|
||||
function finalize() {
|
||||
|
|
|
@ -1,5 +1,7 @@
|
|||
'use strict';
|
||||
|
||||
const path = require('path');
|
||||
|
||||
TABS.ports = {};
|
||||
|
||||
var portFunctionRules;
|
||||
|
|
|
@ -47,7 +47,7 @@ TABS.setup.initialize = function (callback) {
|
|||
|
||||
function process_html() {
|
||||
// translate to user-selected language
|
||||
i18n.localize();;
|
||||
i18n.localize();
|
||||
|
||||
if (!FC.isMotorOutputEnabled()) {
|
||||
GUI.log("<span style='color: red; font-weight: bolder'><strong>" + i18n.getMessage("logPwmOutputDisabled") + "</strong></span>");
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue