1
0
Fork 0
mirror of https://github.com/iNavFlight/inav-configurator.git synced 2025-07-24 00:35:20 +03:00

Merge remote-tracking branch 'iNavFlight/master' into magnetometer_tab_improvments

# Conflicts:
#	_locales/en/messages.json
This commit is contained in:
Luca 2022-03-26 15:50:02 +01:00
commit ce0b4dac66
72 changed files with 2879 additions and 2488 deletions

View file

@ -1,4 +1,4 @@
/*global mspHelper,$,GUI,MSP,BF_CONFIG,chrome*/
/*global mspHelper,$,GUI,MSP,chrome*/
'use strict';
var helper = helper || {};
@ -16,7 +16,12 @@ helper.defaultsDialog = (function () {
"id": 2,
"notRecommended": false,
"reboot": true,
"mixerToApply": 3,
"settings": [
{
key: "model_preview_type",
value: 3
},
/*
System
*/
@ -198,7 +203,12 @@ helper.defaultsDialog = (function () {
"notRecommended": false,
"id": 3,
"reboot": true,
"mixerToApply": 14,
"settings": [
{
key: "model_preview_type",
value: 14
},
{
key: "platform_type",
value: "AIRPLANE"
@ -392,7 +402,12 @@ helper.defaultsDialog = (function () {
"notRecommended": false,
"id": 3,
"reboot": true,
"mixerToApply": 8,
"settings": [
{
key: "model_preview_type",
value: 8
},
{
key: "platform_type",
value: "AIRPLANE"
@ -586,7 +601,12 @@ helper.defaultsDialog = (function () {
"id": 1,
"notRecommended": false,
"reboot": true,
"mixerToApply": 31,
"settings": [
{
key: "model_preview_type",
value: 31
},
{
key: "gyro_hardware_lpf",
value: "256HZ"
@ -685,6 +705,24 @@ helper.defaultsDialog = (function () {
}
};
privateScope.finalize = function (selectedDefaultPreset) {
mspHelper.saveToEeprom(function () {
//noinspection JSUnresolvedVariable
GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
if (selectedDefaultPreset.reboot) {
GUI.tab_switch_cleanup(function () {
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, function () {
//noinspection JSUnresolvedVariable
savingDefaultsModal.close();
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
GUI.handleReconnect();
});
});
}
});
};
privateScope.setSettings = function (selectedDefaultPreset) {
//Save analytics
googleAnalytics.sendEvent('Setting', 'Defaults', selectedDefaultPreset.title);
@ -694,21 +732,30 @@ helper.defaultsDialog = (function () {
Promise.mapSeries(selectedDefaultPreset.settings, function (input, ii) {
return mspHelper.setSetting(input.key, input.value);
}).then(function () {
mspHelper.saveToEeprom(function () {
//noinspection JSUnresolvedVariable
GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
if (selectedDefaultPreset.reboot) {
GUI.tab_switch_cleanup(function () {
MSP.send_message(MSPCodes.MSP_SET_REBOOT, false, false, function () {
//noinspection JSUnresolvedVariable
savingDefaultsModal.close();
GUI.log(chrome.i18n.getMessage('deviceRebooting'));
GUI.handleReconnect();
});
});
}
});
// If default preset is associated to a mixer, apply the mixer as well
if (selectedDefaultPreset.mixerToApply) {
let currentMixerPreset = helper.mixer.getById(selectedDefaultPreset.mixerToApply);
helper.mixer.loadServoRules(currentMixerPreset);
helper.mixer.loadMotorRules(currentMixerPreset);
SERVO_RULES.cleanup();
SERVO_RULES.inflate();
MOTOR_RULES.cleanup();
MOTOR_RULES.inflate();
mspHelper.sendServoMixer(function () {
mspHelper.sendMotorMixer(function () {
privateScope.finalize(selectedDefaultPreset);
})
});
} else {
privateScope.finalize(selectedDefaultPreset);
}
})
});
};
@ -733,7 +780,7 @@ helper.defaultsDialog = (function () {
savingDefaultsModal.close();
}
mspHelper.loadBfConfig(function () {
mspHelper.loadFeatures(function () {
privateScope.setFeaturesBits(selectedDefaultPreset)
});
} else {

592
js/fc.js
View file

@ -2,7 +2,6 @@
// define all the global variables that are uses to hold FC state
var CONFIG,
BF_CONFIG,
LED_STRIP,
LED_COLORS,
LED_MODE_COLORS,
@ -39,7 +38,6 @@ var CONFIG,
DATAFLASH,
SDCARD,
BLACKBOX,
TRANSPONDER,
RC_deadband,
SENSOR_ALIGNMENT,
RX_CONFIG,
@ -63,9 +61,13 @@ var CONFIG,
OUTPUT_MAPPING,
SETTINGS,
BRAKING_CONFIG,
SAFEHOMES;
SAFEHOMES,
BOARD_ALIGNMENT,
CURRENT_METER_CONFIG,
FEATURES;
var FC = {
restartRequired: false,
MAX_SERVO_RATE: 125,
MIN_SERVO_RATE: 0,
isAirplane: function () {
@ -75,14 +77,11 @@ var FC = {
return (MIXER_CONFIG.platformType == PLATFORM_MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM_TRICOPTER);
},
isRpyFfComponentUsed: function () {
return (MIXER_CONFIG.platformType == PLATFORM_AIRPLANE || MIXER_CONFIG.platformType == PLATFORM_ROVER || MIXER_CONFIG.platformType == PLATFORM_BOAT) || ((MIXER_CONFIG.platformType == PLATFORM_MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM_TRICOPTER) && semver.gte(CONFIG.flightControllerVersion, "2.6.0"));
return true; // Currently all planes have roll, pitch and yaw FF
},
isRpyDComponentUsed: function () {
return true; // Currently all platforms use D term
},
isCdComponentUsed: function () {
return (MIXER_CONFIG.platformType == PLATFORM_MULTIROTOR || MIXER_CONFIG.platformType == PLATFORM_TRICOPTER);
},
resetState: function () {
SENSOR_STATUS = {
isHardwareHealthy: 0,
@ -127,21 +126,25 @@ var FC = {
name: ''
};
BF_CONFIG = {
mixerConfiguration: 0,
features: 0,
serialrx_type: 0,
board_align_roll: 0,
board_align_pitch: 0,
board_align_yaw: 0,
currentscale: 0,
currentoffset: 0
BOARD_ALIGNMENT = {
roll: 0,
pitch: 0,
yaw: 0
};
CURRENT_METER_CONFIG = {
scale: 0,
offset: 0,
type: 0,
capacity: 0
};
LED_STRIP = [];
LED_COLORS = [];
LED_MODE_COLORS = [];
FEATURES = 0;
PID = {
};
@ -246,23 +249,6 @@ var FC = {
packetCount: 0
};
/* MISSION_PLANNER = {
maxWaypoints: 0,
isValidMission: 0,
countBusyPoints: 0,
bufferPoint: {
number: 0,
action: 0,
lat: 0,
lon: 0,
alt: 0,
endMission: 0,
p1: 0,
p2: 0,
p3: 0
}
}; */
MISSION_PLANNER = new WaypointCollection();
ANALOG = {
@ -473,11 +459,6 @@ var FC = {
blackboxRateDenom: 1
};
TRANSPONDER = {
supported: false,
data: []
};
RC_deadband = {
deadband: 0,
yaw_deadband: 0,
@ -576,7 +557,7 @@ var FC = {
{bit: 1, group: 'batteryVoltage', name: 'VBAT'},
{bit: 4, group: 'other', name: 'MOTOR_STOP'},
{bit: 6, group: 'other', name: 'SOFTSERIAL', haveTip: true, showNameInTip: true},
{bit: 7, group: 'gps', name: 'GPS', haveTip: true},
{bit: 7, group: 'other', name: 'GPS', haveTip: true},
{bit: 10, group: 'other', name: 'TELEMETRY', showNameInTip: true},
{bit: 11, group: 'batteryCurrent', name: 'CURRENT_METER'},
{bit: 12, group: 'other', name: 'REVERSIBLE_MOTORS', showNameInTip: true},
@ -595,10 +576,6 @@ var FC = {
{bit: 31, group: 'other', name: "FW_AUTOTRIM", haveTip: true, showNameInTip: true}
];
if (semver.gte(CONFIG.flightControllerVersion, "2.4.0") && semver.lt(CONFIG.flightControllerVersion, "2.5.0")) {
features.push({bit: 5, group: 'other', name: 'DYNAMIC_FILTERS', haveTip: true, showNameInTip: true});
}
return features.reverse();
},
isFeatureEnabled: function (featureName, features) {
@ -606,7 +583,7 @@ var FC = {
features = this.getFeatures();
}
for (var i = 0; i < features.length; i++) {
if (features[i].name == featureName && bit_check(BF_CONFIG.features, features[i].bit)) {
if (features[i].name == featureName && bit_check(FEATURES, features[i].bit)) {
return true;
}
}
@ -658,168 +635,69 @@ var FC = {
];
},
getEscProtocols: function () {
if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
return {
0: {
name: "STANDARD",
message: null,
defaultRate: 400,
rates: {
50: "50Hz",
400: "400Hz"
}
},
1: {
name: "ONESHOT125",
message: null,
defaultRate: 1000,
rates: {
1000: "1kHz",
2000: "2kHz"
}
},
2: {
name: "MULTISHOT",
message: null,
defaultRate: 2000,
rates: {
1000: "1kHz",
2000: "2kHz"
}
},
3: {
name: "BRUSHED",
message: null,
defaultRate: 8000,
rates: {
8000: "8kHz",
16000: "16kHz",
32000: "32kHz"
}
},
4: {
name: "DSHOT150",
message: null,
defaultRate: 4000,
rates: {
4000: "4kHz"
}
},
5: {
name: "DSHOT300",
message: null,
defaultRate: 8000,
rates: {
8000: "8kHz"
}
},
6: {
name: "DSHOT600",
message: null,
defaultRate: 16000,
rates: {
16000: "16kHz"
}
return {
0: {
name: "STANDARD",
message: null,
defaultRate: 400,
rates: {
50: "50Hz",
400: "400Hz"
}
};
} else {
return {
0: {
name: "STANDARD",
message: null,
defaultRate: 400,
rates: {
50: "50Hz",
400: "400Hz"
}
},
1: {
name: "ONESHOT125",
message: null,
defaultRate: 1000,
rates: {
400: "400Hz",
1000: "1kHz",
2000: "2kHz"
}
},
2: {
name: "ONESHOT42",
message: null,
defaultRate: 2000,
rates: {
400: "400Hz",
1000: "1kHz",
2000: "2kHz",
4000: "4kHz",
8000: "8kHz"
}
},
3: {
name: "MULTISHOT",
message: null,
defaultRate: 2000,
rates: {
400: "400Hz",
1000: "1kHz",
2000: "2kHz",
4000: "4kHz",
8000: "8kHz"
}
},
4: {
name: "BRUSHED",
message: null,
defaultRate: 8000,
rates: {
8000: "8kHz",
16000: "16kHz",
32000: "32kHz"
}
},
5: {
name: "DSHOT150",
message: null,
defaultRate: 4000,
rates: {
4000: "4kHz"
}
},
6: {
name: "DSHOT300",
message: null,
defaultRate: 8000,
rates: {
8000: "8kHz"
}
},
7: {
name: "DSHOT600",
message: null,
defaultRate: 16000,
rates: {
16000: "16kHz"
}
},
8: {
name: "DSHOT1200",
message: "escProtocolNotAdvised",
defaultRate: 16000,
rates: {
16000: "16kHz"
}
},
9: {
name: "SERIALSHOT",
message: "escProtocolExperimental",
defaultRate: 4000,
rates: {
4000: "4kHz"
}
},
1: {
name: "ONESHOT125",
message: null,
defaultRate: 1000,
rates: {
1000: "1kHz",
2000: "2kHz"
}
};
}
},
2: {
name: "MULTISHOT",
message: null,
defaultRate: 2000,
rates: {
1000: "1kHz",
2000: "2kHz"
}
},
3: {
name: "BRUSHED",
message: null,
defaultRate: 8000,
rates: {
8000: "8kHz",
16000: "16kHz",
32000: "32kHz"
}
},
4: {
name: "DSHOT150",
message: null,
defaultRate: 4000,
rates: {
4000: "4kHz"
}
},
5: {
name: "DSHOT300",
message: null,
defaultRate: 8000,
rates: {
8000: "8kHz"
}
},
6: {
name: "DSHOT600",
message: null,
defaultRate: 16000,
rates: {
16000: "16kHz"
}
}
};
},
getServoRates: function () {
return {
@ -860,37 +738,6 @@ var FC = {
getOsdDisabledFields: function () {
return [];
},
getAccelerometerNames: function () {
return [ "NONE", "AUTO", "MPU6050", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "FAKE"];
},
getBarometerNames: function () {
if (semver.gte(CONFIG.flightControllerVersion, "2.6.0")) {
return ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "BMP388", "DPS310", "MSP", "FAKE"];
} else {
return ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "BMP388", "FAKE"];
}
},
getPitotNames: function () {
if (semver.gte(CONFIG.flightControllerVersion, "2.6.0")) {
return ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE", "MSP"];
} else {
return ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE"];
}
},
getRangefinderNames: function () {
if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
return [ "NONE", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "Benewake TFmini", "VL53L1X", "US42"];
} else {
return [ "NONE", "HCSR04", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "UIB", "Benewake TFmini"];
}
},
getOpticalFlowNames: function () {
if (semver.gte(CONFIG.flightControllerVersion, "2.7.0")) {
return [ "NONE", "CXOF", "MSP", "FAKE" ];
} else {
return [ "NONE", "PMW3901", "CXOF", "MSP", "FAKE" ];
}
},
getArmingFlags: function () {
return {
0: "OK_TO_ARM",
@ -927,7 +774,7 @@ var FC = {
]
},
getPidNames: function () {
let list = [
return [
'Roll',
'Pitch',
'Yaw',
@ -937,14 +784,9 @@ var FC = {
'Surface',
'Level',
'Heading Hold',
'Velocity Z'
'Velocity Z',
'Nav Heading'
];
if (semver.gte(CONFIG.flightControllerVersion, '2.5.0')) {
list.push("Nav Heading")
}
return list;
},
getRthAltControlMode: function () {
return ["Current", "Extra", "Fixed", "Max", "At least", "At least, linear descent"];
@ -1045,222 +887,266 @@ var FC = {
return {
0: {
name: "True",
operandType: "Active",
hasOperand: [false, false],
output: "boolean"
},
1: {
name: "Equal",
operandType: "Comparison",
hasOperand: [true, true],
output: "boolean"
},
2: {
name: "Greater Than",
operandType: "Comparison",
hasOperand: [true, true],
output: "boolean"
},
3: {
name: "Lower Than",
operandType: "Comparison",
hasOperand: [true, true],
output: "boolean"
},
4: {
name: "Low",
operandType: "RC Switch Check",
hasOperand: [true, false],
output: "boolean"
},
5: {
name: "Mid",
operandType: "RC Switch Check",
hasOperand: [true, false],
output: "boolean"
},
6: {
name: "High",
operandType: "RC Switch Check",
hasOperand: [true, false],
output: "boolean"
},
7: {
name: "AND",
operandType: "Logic Switches",
hasOperand: [true, true],
output: "boolean"
},
8: {
name: "OR",
operandType: "Logic Switches",
hasOperand: [true, true],
output: "boolean"
},
9: {
name: "XOR",
operandType: "Logic Switches",
hasOperand: [true, true],
output: "boolean"
},
10: {
name: "NAND",
operandType: "Logic Switches",
hasOperand: [true, true],
output: "boolean"
},
11: {
name: "NOR",
operandType: "Logic Switches",
hasOperand: [true, true],
output: "boolean"
},
12: {
name: "NOT",
operandType: "Logic Switches",
hasOperand: [true, false],
output: "boolean"
},
13: {
name: "STICKY",
name: "Sticky",
operandType: "Logic Switches",
hasOperand: [true, true],
output: "boolean"
},
14: {
name: "ADD",
name: "Basic: Add",
operandType: "Maths",
hasOperand: [true, true],
output: "raw"
},
15: {
name: "SUB",
name: "Basic: Subtract",
operandType: "Maths",
hasOperand: [true, true],
output: "raw"
},
16: {
name: "MUL",
name: "Basic: Multiply",
operandType: "Maths",
hasOperand: [true, true],
output: "raw"
},
17: {
name: "DIV",
name: "Basic: Divide",
operandType: "Maths",
hasOperand: [true, true],
output: "raw"
},
40: {
name: "MOD",
name: "Modulo",
operandType: "Maths",
hasOperand: [true, true],
output: "raw"
},
18: {
name: "GVAR SET",
name: "Set GVAR",
operandType: "Variables",
hasOperand: [true, true],
output: "none"
},
19: {
name: "GVAR INC",
name: "Increase GVAR",
operandType: "Variables",
hasOperand: [true, true],
output: "none"
},
20: {
name: "GVAR DEC",
name: "Decrease GVAR",
operandType: "Variables",
hasOperand: [true, true],
output: "none"
},
21: {
name: "IO PORT SET",
name: "Set IO Port",
operandType: "Set Flight Parameter",
hasOperand: [true, true],
output: "none"
},
22: {
name: "OVERRIDE ARMING SAFETY",
name: "Override Arming Safety",
operandType: "Set Flight Parameter",
hasOperand: [false, false],
output: "boolean"
},
23: {
name: "OVERRIDE THROTTLE SCALE",
name: "Override Throttle Scale",
operandType: "Set Flight Parameter",
hasOperand: [true, false],
output: "boolean"
},
29: {
name: "OVERRIDE THROTTLE",
name: "Override Throttle",
operandType: "Set Flight Parameter",
hasOperand: [true, false],
output: "boolean"
},
24: {
name: "SWAP ROLL & YAW",
name: "Swap Roll & Yaw",
operandType: "Set Flight Parameter",
hasOperand: [false, false],
output: "boolean"
},
25: {
name: "SET VTX POWER LEVEL",
name: "Set VTx Power Level",
operandType: "Set Flight Parameter",
hasOperand: [true, false],
output: "boolean"
},
30: {
name: "SET VTX BAND",
name: "Set VTx Band",
operandType: "Set Flight Parameter",
hasOperand: [true, false],
output: "boolean"
},
31: {
name: "SET VTX CHANNEL",
name: "Set VTx Channel",
operandType: "Set Flight Parameter",
hasOperand: [true, false],
output: "boolean"
},
26: {
name: "INVERT ROLL",
name: "Invert Roll",
operandType: "Set Flight Parameter",
hasOperand: [false, false],
output: "boolean"
},
27: {
name: "INVERT PITCH",
name: "Invert Pitch",
operandType: "Set Flight Parameter",
hasOperand: [false, false],
output: "boolean"
},
28: {
name: "INVERT YAW",
name: "Invert Yaw",
operandType: "Set Flight Parameter",
hasOperand: [false, false],
output: "boolean"
},
32: {
name: "SET OSD LAYOUT",
name: "Set OSD Layout",
operandType: "Set Flight Parameter",
hasOperand: [true, false],
output: "boolean"
},
33: {
name: "SIN",
name: "Trigonometry: Sine",
operandType: "Maths",
hasOperand: [true, true],
output: "raw"
},
34: {
name: "COS",
name: "Trigonometry: Cosine",
operandType: "Maths",
hasOperand: [true, true],
output: "raw"
},
35: {
name: "TAN",
name: "Trigonometry: Tangent",
operandType: "Maths",
hasOperand: [true, true],
output: "raw"
},
36: {
name: "MAP INPUT",
name: "Map Input",
operandType: "Maths",
hasOperand: [true, true],
output: "raw"
},
37: {
name: "MAP OUTPUT",
name: "Map Output",
operandType: "Maths",
hasOperand: [true, true],
output: "raw"
},
38: {
name: "RC CHANNEL OVERRIDE",
name: "Override RC Channel",
operandType: "Set Flight Parameter",
hasOperand: [true, true],
output: "boolean"
},
41: {
name: "LOITER RADIUS OVERRIDE",
name: "Override Loiter Radius",
operandType: "Set Flight Parameter",
hasOperand: [true, false],
output: "boolean"
},
42: {
name: "SET PROFILE",
name: "Set Profile",
operandType: "Set Flight Parameter",
hasOperand: [true, false],
output: "boolean"
},
43: {
name: "MIN",
name: "Use Lowest Value",
operandType: "Comparison",
hasOperand: [true, true],
output: "raw"
},
44: {
name: "MAX",
name: "Use Highest Value",
operandType: "Comparison",
hasOperand: [true, true],
output: "raw"
},
@ -1324,6 +1210,7 @@ var FC = {
34: "GPS Valid Fix",
35: "Loiter Radius [cm]",
36: "Active Profile",
37: "Battery cells",
}
},
3: {
@ -1363,5 +1250,162 @@ var FC = {
default: 0
}
}
},
getBatteryProfileParameters: function () {
return [
'bat_cells',
'vbat_cell_detect_voltage',
'vbat_max_cell_voltage',
'vbat_min_cell_voltage',
'vbat_warning_cell_voltage',
'battery_capacity',
'battery_capacity_warning',
'battery_capacity_critical',
'battery_capacity_unit',
'controlrate_profile',
'throttle_scale',
'throttle_idle',
'turtle_mode_power_factor',
'failsafe_throttle',
'fw_min_throttle_down_pitch',
'nav_mc_hover_thr',
'nav_fw_cruise_thr',
'nav_fw_min_thr',
'nav_fw_max_thr',
'nav_fw_pitch2thr',
'nav_fw_launch_thr',
'nav_fw_launch_idle_thr',
'limit_cont_current',
'limit_burst_current',
'limit_burst_current_time',
'limit_burst_current_falldown_time',
'limit_cont_power',
'limit_burst_power',
'limit_burst_power_time',
'limit_burst_power_falldown_time'
];
},
isBatteryProfileParameter: function(paramName) {
return ($.inArray(paramName,this.getBatteryProfileParameters()) != -1);
},
getControlProfileParameters: function () {
return [
'mc_p_pitch',
'mc_i_pitch',
'mc_d_pitch',
'mc_cd_pitch',
'mc_p_roll',
'mc_i_roll',
'mc_d_roll',
'mc_cd_roll',
'mc_p_yaw',
'mc_i_yaw',
'mc_d_yaw',
'mc_cd_yaw',
'mc_p_level',
'mc_i_level',
'mc_d_level',
'fw_p_pitch',
'fw_i_pitch',
'fw_d_pitch',
'fw_ff_pitch',
'fw_p_roll',
'fw_i_roll',
'fw_d_roll',
'fw_ff_roll',
'fw_p_yaw',
'fw_i_yaw',
'fw_d_yaw',
'fw_ff_yaw',
'fw_p_level',
'fw_i_level',
'fw_d_level',
'max_angle_inclination_rll',
'max_angle_inclination_pit',
'dterm_lpf_hz',
'dterm_lpf_type',
'dterm_lpf2_hz',
'dterm_lpf2_type',
'yaw_lpf_hz',
'fw_iterm_throw_limit',
'fw_loiter_direction',
'fw_reference_airspeed',
'fw_turn_assist_yaw_gain',
'fw_turn_assist_pitch_gain',
'fw_iterm_limit_stick_position',
'fw_yaw_iterm_freeze_bank_angle',
'pidsum_limit',
'pidsum_limit_yaw',
'iterm_windup',
'rate_accel_limit_roll_pitch',
'rate_accel_limit_yaw',
'heading_hold_rate_limit',
'nav_mc_pos_z_p',
'nav_mc_vel_z_p',
'nav_mc_vel_z_i',
'nav_mc_vel_z_d',
'nav_mc_pos_xy_p',
'nav_mc_vel_xy_p',
'nav_mc_vel_xy_i',
'nav_mc_vel_xy_d',
'nav_mc_vel_xy_ff',
'nav_mc_heading_p',
'nav_mc_vel_xy_dterm_lpf_hz',
'nav_mc_vel_xy_dterm_attenuation',
'nav_mc_vel_xy_dterm_attenuation_start',
'nav_mc_vel_xy_dterm_attenuation_end',
'nav_fw_pos_z_p',
'nav_fw_pos_z_i',
'nav_fw_pos_z_d',
'nav_fw_pos_xy_p',
'nav_fw_pos_xy_i',
'nav_fw_pos_xy_d',
'nav_fw_heading_p',
'nav_fw_pos_hdg_p',
'nav_fw_pos_hdg_i',
'nav_fw_pos_hdg_d',
'nav_fw_pos_hdg_pidsum_limit',
'mc_iterm_relax',
'mc_iterm_relax_cutoff',
'd_boost_min',
'd_boost_max',
'd_boost_max_at_acceleration',
'd_boost_gyro_delta_lpf_hz',
'antigravity_gain',
'antigravity_accelerator',
'antigravity_cutoff_lpf_hz',
'pid_type',
'mc_cd_lpf_hz',
'fw_level_pitch_trim',
'smith_predictor_strength',
'smith_predictor_delay',
'smith_predictor_lpf_hz',
'fw_level_pitch_gain',
'thr_mid',
'thr_expo',
'tpa_rate',
'tpa_breakpoint',
'fw_tpa_time_constant',
'rc_expo',
'rc_yaw_expo',
'roll_rate',
'pitch_rate',
'yaw_rate',
'manual_rc_expo',
'manual_rc_yaw_expo',
'manual_roll_rate',
'manual_pitch_rate',
'manual_yaw_rate',
'fpv_mix_degrees',
'rate_dynamics_center_sensitivity',
'rate_dynamics_end_sensitivity',
'rate_dynamics_center_correction',
'rate_dynamics_end_correction',
'rate_dynamics_center_weight',
'rate_dynamics_end_weight'
];
},
isControlProfileParameter: function(paramName) {
return ($.inArray(paramName, this.getControlProfileParameters()) != -1);
}
};

View file

@ -1,4 +1,4 @@
/*global mspHelper,BF_CONFIG*/
/*global mspHelper,FEATURES,bit_clear,bit_set*/
'use strict';
var helper = helper || {};
@ -67,20 +67,20 @@ helper.features = (function() {
publicScope.execute = function(callback) {
exitPoint = callback;
mspHelper.loadBfConfig(privateScope.setBits);
mspHelper.loadFeatures(privateScope.setBits);
};
privateScope.setBits = function () {
for (const bit of toSet) {
BF_CONFIG.features = bit_set(BF_CONFIG.features, bit);
FEATURES = bit_set(FEATURES, bit);
}
for (const bit of toUnset) {
BF_CONFIG.features = bit_clear(BF_CONFIG.features, bit);
FEATURES = bit_clear(FEATURES, bit);
}
mspHelper.saveBfConfig(exitPoint);
mspHelper.saveFeatures(exitPoint);
}
return publicScope;

View file

@ -18,7 +18,6 @@ var GUI_control = function () {
];
this.defaultAllowedTabsWhenConnected = [
'failsafe',
'transponder',
'adjustments',
'auxiliary',
'cli',

View file

@ -256,16 +256,55 @@ let LogicCondition = function (enabled, activatorId, operation, operandAType, op
$row.find('.logic_cell__operation').html("<select class='logic_element__operation' ></select>");
let $t = $row.find('.logic_element__operation');
for (let k in FC.getLogicOperators()) {
if (FC.getLogicOperators().hasOwnProperty(k)) {
let o = FC.getLogicOperators()[k];
if (self.getOperation() == parseInt(k, 10)) {
$t.append('<option value="' + k + '" selected>' + o.name + '</option>');
} else {
$t.append('<option value="' + k + '">' + o.name + '</option>');
}
let lcOperators = [];
for (let lcID in FC.getLogicOperators()) {
if (FC.getLogicOperators().hasOwnProperty(lcID)) {
let op = FC.getLogicOperators()[lcID];
lcOperators[parseInt(lcID, 10)] = {
id: parseInt(lcID, 10),
name: op.name,
operandType: op.operandType,
hasOperand: op.hasOperand,
output: op.output
};
}
}
lcOperators.sort((a, b) => {
let lcAT = a.operandType.toLowerCase(),
lcBT = b.operandType.toLowerCase(),
lcAN = a.name.toLowerCase(),
lcBN = b.name.toLowerCase();
if (lcAT == lcBT) {
return (lcAN < lcBN) ? -1 : (lcAN > lcBN) ? 1 : 0;
} else {
return (lcAT < lcBT) ? -1 : 1;
}
});
let section = "";
lcOperators.forEach( val => {
if (section != val.operandType) {
if (section != "") {
$t.append('</optgroup>');
}
section = val.operandType;
$t.append('<optgroup label="** ' + val.operandType + ' **">');
}
if (self.getOperation() == val.id) {
$t.append('<option value="' + val.id + '" selected>' + val.name + '</option>');
} else {
$t.append('<option value="' + val.id + '">' + val.name + '</option>');
}
});
$t.append('</optgroup>');
$t.change(self.onOperatorChange);
self.renderOperand(0);

View file

@ -44,6 +44,7 @@ const
// generate mixer
const mixerList = [
// ** Multirotor
{
id: 1,
name: 'Tricopter',
@ -60,7 +61,7 @@ const mixerList = [
servoMixer: [
new ServoMixRule(SERVO_RUDDER, INPUT_STABILIZED_YAW, 100, 0),
]
}, // 1
}, // 1
{
id: 3,
name: 'Quad X',
@ -76,7 +77,7 @@ const mixerList = [
new MotorMixRule(1.0, 1.0, -1.0, -1.0), // FRONT_L
],
servoMixer: []
}, // 3
}, // 3
{
id: 2,
name: 'Quad +',
@ -92,7 +93,7 @@ const mixerList = [
new MotorMixRule(1.0, 0.0, -1.0, -1.0), // FRONT
],
servoMixer: []
}, // 2
}, // 2
{
id: 4,
name: 'Bicopter',
@ -103,18 +104,7 @@ const mixerList = [
platform: PLATFORM_MULTIROTOR,
motorMixer: [],
servoMixer: []
}, // 4
{
id: 5,
name: 'Gimbal',
model: 'custom',
image: 'custom',
enabled: false,
legacy: true,
platform: PLATFORM_OTHER,
motorMixer: [],
servoMixer: []
}, // 5
}, // 4
{
id: 6,
name: 'Y6',
@ -132,7 +122,7 @@ const mixerList = [
new MotorMixRule(1.0, 1.0, -0.666667, 1.0), // UNDER_LEFT
],
servoMixer: []
}, // 6
}, // 6
{
id: 7,
name: 'Hex +',
@ -150,45 +140,7 @@ const mixerList = [
new MotorMixRule(1.0, 0.0, 1.0, -1.0), // REAR
],
servoMixer: []
}, // 7
{
id: 8,
name: 'Flying Wing',
model: 'flying_wing',
image: 'flying_wing',
enabled: true,
legacy: true,
platform: PLATFORM_AIRPLANE,
motorMixer: [
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
],
servoMixer: [
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_ROLL, 50, 0),
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_PITCH, 50, 0),
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_ROLL, -50, 0),
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_PITCH, 50, 0),
]
}, // 8
{
id: 27,
name: 'Flying Wing with differential thrust',
model: 'flying_wing',
image: 'flying_wing',
enabled: true,
legacy: false,
platform: PLATFORM_AIRPLANE,
motorMixer: [
new MotorMixRule(1.0, 0.0, 0.0, 0.1),
new MotorMixRule(1.0, 0.0, 0.0, -0.1)
],
servoMixer: [
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_ROLL, 50, 0),
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_PITCH, 50, 0),
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_ROLL, -50, 0),
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_PITCH, 50, 0),
]
}, // 27
}, // 7
{
id: 9,
name: 'Y4',
@ -204,7 +156,7 @@ const mixerList = [
new MotorMixRule(1.0, 1.0, -1.0, 0.0), // FRONT_L CW
],
servoMixer: []
}, // 9
}, // 9
{
id: 10,
name: 'Hex X',
@ -222,7 +174,7 @@ const mixerList = [
new MotorMixRule(1.0, 1.0, 0.0, 1.0), // LEFT
],
servoMixer: []
}, // 10
}, // 10
{
id: 11,
name: 'Octo X8',
@ -242,7 +194,7 @@ const mixerList = [
new MotorMixRule(1.0, 1.0, -1.0, 1.0), // UNDER_FRONT_L
],
servoMixer: []
}, // 11
}, // 11
{
id: 12,
name: 'Octo Flat +',
@ -262,7 +214,7 @@ const mixerList = [
new MotorMixRule(1.0, 1.0, 0.0, -1.0), // LEFT
],
servoMixer: []
}, // 12
}, // 12
{
id: 13,
name: 'Octo Flat X',
@ -282,51 +234,7 @@ const mixerList = [
new MotorMixRule(1.0, 1.0, 0.414178, -1.0), // MIDREAR_L
],
servoMixer: []
}, // 13
{
id: 14,
name: 'Airplane',
model: 'twin_plane',
image: 'airplane',
enabled: true,
legacy: true,
platform: PLATFORM_AIRPLANE,
hasFlaps: true,
motorMixer: [
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
],
servoMixer: [
new ServoMixRule(SERVO_ELEVATOR, INPUT_STABILIZED_PITCH, 100, 0),
new ServoMixRule(SERVO_FLAPPERON_1, INPUT_STABILIZED_ROLL, 100, 0),
/*new ServoMixRule(SERVO_FLAPPERON_1, INPUT_FEATURE_FLAPS, 100, 0),*/
new ServoMixRule(SERVO_FLAPPERON_2, INPUT_STABILIZED_ROLL, 100, 0),
/*new ServoMixRule(SERVO_FLAPPERON_2, INPUT_FEATURE_FLAPS, -100, 0),*/
new ServoMixRule(SERVO_RUDDER, INPUT_STABILIZED_YAW, 100, 0),
]
}, // 14
{
id: 15,
name: 'Heli 120',
model: 'custom',
image: 'custom',
enabled: false,
legacy: true,
platform: PLATFORM_HELICOPTER,
motorMixer: [],
servoMixer: []
}, // 15
{
id: 16,
name: 'Heli 90',
model: 'custom',
image: 'custom',
enabled: false,
legacy: true,
platform: PLATFORM_HELICOPTER,
motorMixer: [],
servoMixer: []
}, // 16
}, // 13
{
id: 17,
name: 'V-tail Quad',
@ -360,18 +268,7 @@ const mixerList = [
new MotorMixRule(1.0, 0.0, 0.0, 0.0), // LEFT
],
servoMixer: []
}, // 18
{
id: 19,
name: 'PPM to SERVO',
model: 'custom',
image: 'custom',
enabled: false,
legacy: true,
platform: PLATFORM_OTHER,
motorMixer: [],
servoMixer: []
}, // 19
}, // 18
{
id: 20,
name: 'Dualcopter',
@ -382,7 +279,7 @@ const mixerList = [
platform: PLATFORM_MULTIROTOR,
motorMixer: [],
servoMixer: []
}, // 20
}, // 20
{
id: 21,
name: 'Singlecopter',
@ -393,7 +290,7 @@ const mixerList = [
platform: PLATFORM_MULTIROTOR,
motorMixer: [],
servoMixer: []
}, // 21
}, // 21
{
id: 22,
name: 'A-tail Quad',
@ -420,18 +317,7 @@ const mixerList = [
platform: PLATFORM_MULTIROTOR,
motorMixer: [],
servoMixer: []
}, // 23
{
id: 24,
name: 'Custom Airplane',
model: 'twin_plane',
image: 'airplane',
enabled: false,
legacy: true,
platform: PLATFORM_AIRPLANE,
motorMixer: [],
servoMixer: []
}, // 24
}, // 23
{
id: 25,
name: 'Custom Tricopter',
@ -442,12 +328,96 @@ const mixerList = [
platform: PLATFORM_TRICOPTER,
motorMixer: [],
servoMixer: []
}, // 25
}, // 25
// ** Fixed Wing **
{
id: 8,
name: 'Flying Wing',
model: 'flying_wing',
image: 'flying_wing',
imageOutputsNumbers: [
{input: INPUT_STABILIZED_ROLL, top: 123, left: 18, colour: "#ff0000"},
{input: INPUT_STABILIZED_ROLL, top: 123, left: 134, colour: "#00e000"},
{input: INPUT_STABILIZED_THROTTLE, top:93, left:71, colour: "#000000"},
],
enabled: true,
legacy: true,
platform: PLATFORM_AIRPLANE,
motorMixer: [
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
],
servoMixer: [
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_ROLL, 50, 0),
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_PITCH, 50, 0),
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_ROLL, -50, 0),
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_PITCH, 50, 0),
]
}, // 8
{
id: 27,
name: 'Flying Wing with differential thrust',
model: 'flying_wing',
image: 'flying_wing',
imageOutputsNumbers: [
{input: INPUT_STABILIZED_ROLL, top: 123, left: 18, colour: "#ff0000"},
{input: INPUT_STABILIZED_ROLL, top: 123, left: 134, colour: "#00e000"},
{input: INPUT_STABILIZED_THROTTLE, top:93, left:71, colour: "#000000"},
],
enabled: true,
legacy: false,
platform: PLATFORM_AIRPLANE,
motorMixer: [
new MotorMixRule(1.0, 0.0, 0.0, 0.1),
new MotorMixRule(1.0, 0.0, 0.0, -0.1)
],
servoMixer: [
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_ROLL, 50, 0),
new ServoMixRule(SERVO_ELEVON_1, INPUT_STABILIZED_PITCH, 50, 0),
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_ROLL, -50, 0),
new ServoMixRule(SERVO_ELEVON_2, INPUT_STABILIZED_PITCH, 50, 0),
]
}, // 27
{
id: 14,
name: 'Airplane',
model: 'twin_plane',
image: 'airplane',
imageOutputsNumbers: [
{input: INPUT_STABILIZED_PITCH, top: 151, left: 126, colour: "#ff7f00"},
{input: INPUT_STABILIZED_ROLL, top: 96, left: 18, colour: "#ff0000"},
{input: INPUT_STABILIZED_ROLL, top: 96, left: 134, colour: "#00e000"},
{input: INPUT_STABILIZED_YAW, top: 126, left: 52, colour: "#00a6ff"},
{input: INPUT_STABILIZED_THROTTLE, top:5, left:71, colour: "#000000"},
],
enabled: true,
legacy: true,
platform: PLATFORM_AIRPLANE,
hasFlaps: true,
motorMixer: [
new MotorMixRule(1.0, 0.0, 0.0, 0.0),
],
servoMixer: [
new ServoMixRule(SERVO_ELEVATOR, INPUT_STABILIZED_PITCH, 100, 0),
new ServoMixRule(SERVO_FLAPPERON_1, INPUT_STABILIZED_ROLL, 100, 0),
/*new ServoMixRule(SERVO_FLAPPERON_1, INPUT_FEATURE_FLAPS, 100, 0),*/
new ServoMixRule(SERVO_FLAPPERON_2, INPUT_STABILIZED_ROLL, 100, 0),
/*new ServoMixRule(SERVO_FLAPPERON_2, INPUT_FEATURE_FLAPS, -100, 0),*/
new ServoMixRule(SERVO_RUDDER, INPUT_STABILIZED_YAW, 100, 0),
]
}, // 14
{
id: 26,
name: 'Airplane with differential thrust',
model: 'twin_plane',
image: 'airplane',
imageOutputsNumbers: [
{input: INPUT_STABILIZED_PITCH, top: 151, left: 126, colour: "#ff7f00"},
{input: INPUT_STABILIZED_ROLL, top: 96, left: 18, colour: "#ff0000"},
{input: INPUT_STABILIZED_ROLL, top: 96, left: 134, colour: "#00e000"},
{input: INPUT_STABILIZED_YAW, top: 126, left: 52, colour: "#00a6ff"},
{input: INPUT_STABILIZED_THROTTLE, top:5, left:71, colour: "#000000"},
],
enabled: true,
legacy: false,
platform: PLATFORM_AIRPLANE,
@ -464,12 +434,19 @@ const mixerList = [
/*new ServoMixRule(SERVO_FLAPPERON_2, INPUT_FEATURE_FLAPS, -100, 0),*/
new ServoMixRule(SERVO_RUDDER, INPUT_STABILIZED_YAW, 100, 0),
]
},
}, // 26
{
id: 28,
name: 'Airplane V-tail (individual aileron servos)',
name: 'Airplane V-tail',
model: 'vtail_plane',
image: 'airplane_vtail',
imageOutputsNumbers: [
{input: INPUT_STABILIZED_ROLL, top: 96, left: 18, colour: "#ff0000"},
{input: INPUT_STABILIZED_ROLL, top: 96, left: 134, colour: "#00e000"},
{input: INPUT_STABILIZED_PITCH, top: 154, left: 20, colour: "#ff7f00"},
{input: INPUT_STABILIZED_PITCH, top: 154, left: 132, colour: "#00a6ff"},
{input: INPUT_STABILIZED_THROTTLE, top:5, left:71, colour: "#000000"},
],
enabled: true,
legacy: false,
platform: PLATFORM_AIRPLANE,
@ -487,12 +464,49 @@ const mixerList = [
new ServoMixRule(4, INPUT_STABILIZED_PITCH, -50, 0),
new ServoMixRule(4, INPUT_STABILIZED_YAW, -50, 0)
]
},
}, // 28
{
id: 34,
name: 'Airplane V-tail with differential thrust',
model: 'vtail_plane',
image: 'airplane_vtail',
imageOutputsNumbers: [
{input: INPUT_STABILIZED_ROLL, top: 96, left: 18, colour: "#ff0000"},
{input: INPUT_STABILIZED_ROLL, top: 96, left: 134, colour: "#00e000"},
{input: INPUT_STABILIZED_PITCH, top: 154, left: 20, colour: "#ff7f00"},
{input: INPUT_STABILIZED_PITCH, top: 154, left: 132, colour: "#00a6ff"},
{input: INPUT_STABILIZED_THROTTLE, top:5, left:71, colour: "#000000"},
],
enabled: true,
legacy: false,
platform: PLATFORM_AIRPLANE,
hasFlaps: true,
motorMixer: [
new MotorMixRule(1.0, 0.0, 0.0, 0.3),
new MotorMixRule(1.0, 0.0, 0.0, -0.3)
],
servoMixer: [
new ServoMixRule(1, INPUT_STABILIZED_ROLL, 100, 0),
/*new ServoMixRule(1, INPUT_FEATURE_FLAPS, 100, 0),*/
new ServoMixRule(2, INPUT_STABILIZED_ROLL, 100, 0),
/*new ServoMixRule(2, INPUT_FEATURE_FLAPS, 100, 0),*/
new ServoMixRule(3, INPUT_STABILIZED_PITCH, 50, 0),
new ServoMixRule(3, INPUT_STABILIZED_YAW, -50, 0),
new ServoMixRule(4, INPUT_STABILIZED_PITCH, -50, 0),
new ServoMixRule(4, INPUT_STABILIZED_YAW, -50, 0)
]
}, // 34
{
id: 29,
name: 'Airplane V-tail (single aileron servo)',
model: 'vtail_single_servo_plane',
image: 'airplane_vtail_single',
imageOutputsNumbers: [
{input: INPUT_STABILIZED_ROLL, top: 96, left: 18, colour: "#ff7f00"},
{input: INPUT_STABILIZED_PITCH, top: 154, left: 20, colour: "#ff0000"},
{input: INPUT_STABILIZED_PITCH, top: 154, left: 132, colour: "#00e000"},
{input: INPUT_STABILIZED_THROTTLE, top:5, left:71, colour: "#000000"},
],
enabled: true,
legacy: false,
platform: PLATFORM_AIRPLANE,
@ -506,12 +520,18 @@ const mixerList = [
new ServoMixRule(3, INPUT_STABILIZED_PITCH, -50, 0),
new ServoMixRule(3, INPUT_STABILIZED_YAW, -50, 0),
]
},
}, //29
{
id: 30,
name: 'Airplane without rudder',
model: 'rudderless_plane',
image: 'airplane_norudder',
imageOutputsNumbers: [
{input: INPUT_STABILIZED_PITCH, top: 151, left: 126, colour: "#ff7f00"},
{input: INPUT_STABILIZED_ROLL, top: 96, left: 18, colour: "#ff0000"},
{input: INPUT_STABILIZED_ROLL, top: 96, left: 134, colour: "#00e000"},
{input: INPUT_STABILIZED_THROTTLE, top:5, left:71, colour: "#000000"},
],
enabled: true,
legacy: false,
platform: PLATFORM_AIRPLANE,
@ -526,7 +546,51 @@ const mixerList = [
new ServoMixRule(SERVO_FLAPPERON_2, INPUT_STABILIZED_ROLL, 100, 0),
/*new ServoMixRule(SERVO_FLAPPERON_2, INPUT_FEATURE_FLAPS, 100, 0),*/
]
},
}, // 30
{
id: 24,
name: 'Custom Airplane',
model: 'twin_plane',
image: 'airplane',
imageOutputsNumbers: [
{input: INPUT_STABILIZED_PITCH, top: 151, left: 126, colour: "#ff7f00"},
{input: INPUT_STABILIZED_ROLL, top: 96, left: 18, colour: "#ff0000"},
{input: INPUT_STABILIZED_ROLL, top: 96, left: 134, colour: "#00e000"},
{input: INPUT_STABILIZED_YAW, top: 126, left: 52, colour: "#00a6ff"},
{input: INPUT_STABILIZED_THROTTLE, top:5, left:71, colour: "#000000"},
],
enabled: false,
legacy: true,
platform: PLATFORM_AIRPLANE,
motorMixer: [],
servoMixer: []
}, // 24
// ** Helicopter **
{
id: 15,
name: 'Heli 120',
model: 'custom',
image: 'custom',
enabled: false,
legacy: true,
platform: PLATFORM_HELICOPTER,
motorMixer: [],
servoMixer: []
}, // 15
{
id: 16,
name: 'Heli 90',
model: 'custom',
image: 'custom',
enabled: false,
legacy: true,
platform: PLATFORM_HELICOPTER,
motorMixer: [],
servoMixer: []
}, // 16
// ** Other platforms **
{
id: 31,
name: 'Rover',
@ -556,8 +620,8 @@ const mixerList = [
servoMixer: [
new ServoMixRule(3, INPUT_STABILIZED_YAW, 100, 0),
]
}
,
},
// ** Misc **
{
id: 33,
name: 'Other',
@ -572,7 +636,29 @@ const mixerList = [
servoMixer: [
new ServoMixRule(3, INPUT_STABILIZED_YAW, 100, 0),
]
}
},
{
id: 5,
name: 'Gimbal',
model: 'custom',
image: 'custom',
enabled: false,
legacy: true,
platform: PLATFORM_OTHER,
motorMixer: [],
servoMixer: []
}, // 5
{
id: 19,
name: 'PPM to SERVO',
model: 'custom',
image: 'custom',
enabled: false,
legacy: true,
platform: PLATFORM_OTHER,
motorMixer: [],
servoMixer: []
}, // 19
];
const platformList = [

View file

@ -7,9 +7,9 @@ var MotorMixRule = function (throttle, roll, pitch, yaw) {
self.fromMsp = function (mspThrottle, mspRoll, mspPitch, mspYaw) {
throttle = mspThrottle / 1000;
roll = (mspRoll / 1000) - 2;
pitch = (mspPitch / 1000) - 2;
yaw = (mspYaw / 1000) - 2;
roll = Math.round(((mspRoll / 1000) - 2) * 1000) / 1000;
pitch = Math.round(((mspPitch / 1000) - 2) * 1000) / 1000;
yaw = Math.round(((mspYaw / 1000) - 2) * 1000) / 1000;
};
self.isUsed = function () {

View file

@ -57,7 +57,7 @@ var MSP = {
CHECKSUM_V1: 16,
CHECKSUM_V2: 17,
},
protocolVersion: 1, // this.constants.PROTOCOL_V1
protocolVersion: 2, // this.constants.PROTOCOL_V2
state: 0, // this.decoder_states.IDLE
message_direction: 1,
code: 0,
@ -72,7 +72,7 @@ var MSP = {
ledDirectionLetters: ['n', 'e', 's', 'w', 'u', 'd'], // in LSB bit order
ledFunctionLetters: ['i', 'w', 'f', 'a', 't', 'r', 'c', 'g', 's', 'b', 'l'], // in LSB bit order
ledBaseFunctionLetters: ['c', 'f', 'a', 'l', 's', 'g', 'r'], // in LSB bit
ledBaseFunctionLetters: ['c', 'f', 'a', 'l', 's', 'g', 'r', 'h'], // in LSB bit
ledOverlayLetters: ['t', 'o', 'b', 'n', 'i', 'w'], // in LSB bit
last_received_timestamp: null,

View file

@ -33,6 +33,12 @@ var MSPCodes = {
MSP_SET_CHANNEL_FORWARDING: 33,
MSP_MODE_RANGES: 34,
MSP_SET_MODE_RANGE: 35,
MSP_FEATURE: 36,
MSP_SET_FEATURE: 37,
MSP_BOARD_ALIGNMENT: 38,
MSP_SET_BOARD_ALIGNMENT: 39,
MSP_CURRENT_METER_CONFIG: 40,
MSP_SET_CURRENT_METER_CONFIG: 41,
MSP_RX_CONFIG: 44,
MSP_SET_RX_CONFIG: 45,
MSP_LED_COLORS: 46,
@ -44,8 +50,6 @@ var MSPCodes = {
MSP_CF_SERIAL_CONFIG: 54,
MSP_SET_CF_SERIAL_CONFIG: 55,
MSP_SONAR: 58,
MSP_PID_CONTROLLER: 59,
MSP_SET_PID_CONTROLLER: 60,
MSP_ARMING_CONFIG: 61,
MSP_SET_ARMING_CONFIG: 62,
MSP_DATAFLASH_SUMMARY: 70,
@ -60,8 +64,6 @@ var MSPCodes = {
MSP_SDCARD_SUMMARY: 79,
MSP_BLACKBOX_CONFIG: 80,
MSP_SET_BLACKBOX_CONFIG: 81,
MSP_TRANSPONDER_CONFIG: 82,
MSP_SET_TRANSPONDER_CONFIG: 83,
MSP_OSD_CONFIG: 84,
MSP_SET_OSD_CONFIG: 85,
MSP_OSD_CHAR_READ: 86,
@ -103,7 +105,7 @@ var MSPCodes = {
MSP_RC_DEADBAND: 125,
MSP_SENSOR_ALIGNMENT: 126,
MSP_LED_STRIP_MODECOLOR:127,
MSP_STATUS_EX: 150,
MSP_STATUS_EX: 150, // Deprecated, do not use.
MSP_SENSOR_STATUS: 151,
MSP_SET_RAW_RC: 200,
@ -149,10 +151,10 @@ var MSPCodes = {
// Additional private MSP for baseflight configurator (yes thats us \o/)
MSP_RX_MAP: 64, // get channel map (also returns number of channels total)
MSP_SET_RX_MAP: 65, // set rc map, numchannels to set comes from MSP_RX_MAP
MSP_BF_CONFIG: 66, // baseflight-specific settings that aren't covered elsewhere
MSP_SET_BF_CONFIG: 67, // baseflight-specific settings save
MSP_BF_CONFIG: 66, // Depreciated
MSP_SET_BF_CONFIG: 67, // Depreciated
MSP_SET_REBOOT: 68, // reboot settings
MSP_BF_BUILD_INFO: 69, // build date as well as some space for future expansion
MSP_BF_BUILD_INFO: 69, // Depreciated
// INAV specific codes
MSPV2_SETTING: 0x1003,

View file

@ -68,36 +68,6 @@ var mspHelper = (function (gui) {
colorCount,
color;
if (!dataHandler.unsupported || dataHandler.unsupported) switch (dataHandler.code) {
case MSPCodes.MSP_IDENT:
//FIXME remove this frame when proven not needed
console.log('Using deprecated msp command: MSP_IDENT');
// Deprecated
CONFIG.version = parseFloat((data.getUint8(0) / 100).toFixed(2));
CONFIG.multiType = data.getUint8(1);
CONFIG.msp_version = data.getUint8(2);
CONFIG.capability = data.getUint32(3, true);
break;
case MSPCodes.MSP_STATUS:
console.log('Using deprecated msp command: MSP_STATUS');
CONFIG.cycleTime = data.getUint16(0, true);
CONFIG.i2cError = data.getUint16(2, true);
CONFIG.activeSensors = data.getUint16(4, true);
CONFIG.mode = data.getUint32(6, true);
CONFIG.profile = data.getUint8(10);
gui.updateProfileChange();
gui.updateStatusBar();
break;
case MSPCodes.MSP_STATUS_EX:
CONFIG.cycleTime = data.getUint16(0, true);
CONFIG.i2cError = data.getUint16(2, true);
CONFIG.activeSensors = data.getUint16(4, true);
CONFIG.profile = data.getUint8(10);
CONFIG.cpuload = data.getUint16(11, true);
CONFIG.armingFlags = data.getUint16(13, true);
gui.updateStatusBar();
gui.updateProfileChange();
break;
case MSPCodes.MSPV2_INAV_STATUS:
CONFIG.cycleTime = data.getUint16(offset, true);
offset += 2;
@ -134,12 +104,7 @@ var mspHelper = (function (gui) {
SENSOR_STATUS.rangeHwStatus = data.getUint8(6);
SENSOR_STATUS.speedHwStatus = data.getUint8(7);
SENSOR_STATUS.flowHwStatus = data.getUint8(8);
if (semver.gte(CONFIG.flightControllerVersion, "3.1.0")) {
SENSOR_STATUS.imu2HwStatus = data.getUint8(9);
} else {
SENSOR_STATUS.imu2HwStatus = 0;
}
SENSOR_STATUS.imu2HwStatus = data.getUint8(9);
sensor_status_ex(SENSOR_STATUS);
break;
@ -293,14 +258,6 @@ var mspHelper = (function (gui) {
RC_tuning.manual_pitch_rate = data.getUint8(offset++);
RC_tuning.manual_yaw_rate = data.getUint8(offset++);
break;
case MSPCodes.MSP_PID:
// PID data arrived, we need to scale it and save to appropriate bank / array
for (i = 0, needle = 0; i < (dataHandler.message_length_expected / 3); i++, needle += 3) {
PIDs[i][0] = data.getUint8(needle);
PIDs[i][1] = data.getUint8(needle + 1);
PIDs[i][2] = data.getUint8(needle + 2);
}
break;
case MSPCodes.MSP2_PID:
// PID data arrived, we need to scale it and save to appropriate bank / array
for (i = 0, needle = 0; i < (dataHandler.message_length_expected / 4); i++, needle += 4) {
@ -640,9 +597,6 @@ var mspHelper = (function (gui) {
break;
case MSPCodes.MSP_SET_RAW_GPS:
break;
case MSPCodes.MSP_SET_PID:
console.log('PID settings saved');
break;
case MSPCodes.MSP2_SET_PID:
console.log('PID settings saved');
break;
@ -734,19 +688,36 @@ var mspHelper = (function (gui) {
case MSPCodes.MSP_SET_RX_MAP:
console.log('RCMAP saved');
break;
case MSPCodes.MSP_BF_CONFIG:
BF_CONFIG.mixerConfiguration = data.getUint8(0);
BF_CONFIG.features = data.getUint32(1, true);
BF_CONFIG.serialrx_type = data.getUint8(5);
BF_CONFIG.board_align_roll = data.getInt16(6, true); // -180 - 360
BF_CONFIG.board_align_pitch = data.getInt16(8, true); // -180 - 360
BF_CONFIG.board_align_yaw = data.getInt16(10, true); // -180 - 360
BF_CONFIG.currentscale = data.getInt16(12, true);
BF_CONFIG.currentoffset = data.getInt16(14, true);
case MSPCodes.MSP_BOARD_ALIGNMENT:
BOARD_ALIGNMENT.roll = data.getInt16(0, true); // -180 - 360
BOARD_ALIGNMENT.pitch = data.getInt16(2, true); // -180 - 360
BOARD_ALIGNMENT.yaw = data.getInt16(4, true); // -180 - 360
break;
case MSPCodes.MSP_SET_BF_CONFIG:
console.log('BF_CONFIG saved');
case MSPCodes.MSP_SET_BOARD_ALIGNMENT:
console.log('MSP_SET_BOARD_ALIGNMENT saved');
break;
case MSPCodes.MSP_CURRENT_METER_CONFIG:
CURRENT_METER_CONFIG.scale = data.getInt16(0, true);
CURRENT_METER_CONFIG.offset = data.getInt16(2, true);
CURRENT_METER_CONFIG.type = data.getUint8(4);
CURRENT_METER_CONFIG.capacity = data.getInt16(5, true);
break;
case MSPCodes.MSP_SET_CURRENT_METER_CONFIG:
console.log('MSP_SET_CURRENT_METER_CONFIG saved');
break;
case MSPCodes.MSP_FEATURE:
FEATURES = data.getUint32(0, true);
break;
case MSPCodes.MSP_SET_FEATURE:
console.log('MSP_SET_FEATURE saved');
break;
case MSPCodes.MSP_SET_REBOOT:
console.log('Reboot request accepted');
break;
@ -800,28 +771,6 @@ var mspHelper = (function (gui) {
console.log('Channel forwarding saved');
break;
case MSPCodes.MSP_CF_SERIAL_CONFIG:
SERIAL_CONFIG.ports = [];
var bytesPerPort = 1 + 2 + 4;
var serialPortCount = data.byteLength / bytesPerPort;
for (i = 0; i < serialPortCount; i++) {
var BAUD_RATES = mspHelper.BAUD_RATES_post1_6_3;
var serialPort = {
identifier: data.getUint8(offset),
functions: mspHelper.serialPortFunctionMaskToFunctions(data.getUint16(offset + 1, true)),
msp_baudrate: BAUD_RATES[data.getUint8(offset + 3)],
sensors_baudrate: BAUD_RATES[data.getUint8(offset + 4)],
telemetry_baudrate: BAUD_RATES[data.getUint8(offset + 5)],
blackbox_baudrate: BAUD_RATES[data.getUint8(offset + 6)]
};
offset += bytesPerPort;
SERIAL_CONFIG.ports.push(serialPort);
}
break;
case MSPCodes.MSP2_CF_SERIAL_CONFIG:
SERIAL_CONFIG.ports = [];
var bytesPerPort = 1 + 4 + 4;
@ -844,7 +793,6 @@ var mspHelper = (function (gui) {
}
break;
case MSPCodes.MSP_SET_CF_SERIAL_CONFIG:
case MSPCodes.MSP2_SET_CF_SERIAL_CONFIG:
console.log('Serial config saved');
break;
@ -1154,17 +1102,6 @@ var mspHelper = (function (gui) {
case MSPCodes.MSP_SET_BLACKBOX_CONFIG:
console.log("Blackbox config saved");
break;
case MSPCodes.MSP_TRANSPONDER_CONFIG:
TRANSPONDER.supported = (data.getUint8(offset++) & 1) != 0;
TRANSPONDER.data = [];
var bytesRemaining = data.byteLength - offset;
for (i = 0; i < bytesRemaining; i++) {
TRANSPONDER.data.push(data.getUint8(offset++));
}
break;
case MSPCodes.MSP_SET_TRANSPONDER_CONFIG:
console.log("Transponder config saved");
break;
case MSPCodes.MSP_VTX_CONFIG:
VTX_CONFIG.device_type = data.getUint8(offset++);
if (VTX_CONFIG.device_type != VTX.DEV_UNKNOWN) {
@ -1300,11 +1237,9 @@ var mspHelper = (function (gui) {
CALIBRATION_DATA.magZero.Z = data.getInt16(17, true);
CALIBRATION_DATA.opflow.Scale = (data.getInt16(19, true) / 256.0);
if (semver.gte(CONFIG.flightControllerVersion, "2.6.0")) {
CALIBRATION_DATA.magGain.X = data.getInt16(21, true);
CALIBRATION_DATA.magGain.Y = data.getInt16(23, true);
CALIBRATION_DATA.magGain.Z = data.getInt16(25, true);
}
CALIBRATION_DATA.magGain.X = data.getInt16(21, true);
CALIBRATION_DATA.magGain.Y = data.getInt16(23, true);
CALIBRATION_DATA.magGain.Z = data.getInt16(25, true);
break;
@ -1494,6 +1429,7 @@ var mspHelper = (function (gui) {
BLACKBOX.blackboxDevice = data.getUint8(1);
BLACKBOX.blackboxRateNum = data.getUint16(2);
BLACKBOX.blackboxRateDenom = data.getUint16(4);
BLACKBOX.blackboxIncludeFlags = data.getUint32(6,true);
break;
case MSPCodes.MSP2_SET_BLACKBOX_CONFIG:
console.log("Blackbox config saved");
@ -1546,7 +1482,7 @@ var mspHelper = (function (gui) {
// fire callback
if (callback) {
callback({'command': dataHandler.code, 'data': data, 'length': dataHandler.message_length_expected});
callback({ 'command': dataHandler.code, 'data': data, 'length': dataHandler.message_length_expected });
}
break;
}
@ -1559,24 +1495,33 @@ var mspHelper = (function (gui) {
i;
switch (code) {
case MSPCodes.MSP_SET_BF_CONFIG:
buffer.push(BF_CONFIG.mixerConfiguration);
buffer.push(specificByte(BF_CONFIG.features, 0));
buffer.push(specificByte(BF_CONFIG.features, 1));
buffer.push(specificByte(BF_CONFIG.features, 2));
buffer.push(specificByte(BF_CONFIG.features, 3));
buffer.push(BF_CONFIG.serialrx_type);
buffer.push(specificByte(BF_CONFIG.board_align_roll, 0));
buffer.push(specificByte(BF_CONFIG.board_align_roll, 1));
buffer.push(specificByte(BF_CONFIG.board_align_pitch, 0));
buffer.push(specificByte(BF_CONFIG.board_align_pitch, 1));
buffer.push(specificByte(BF_CONFIG.board_align_yaw, 0));
buffer.push(specificByte(BF_CONFIG.board_align_yaw, 1));
buffer.push(lowByte(BF_CONFIG.currentscale));
buffer.push(highByte(BF_CONFIG.currentscale));
buffer.push(lowByte(BF_CONFIG.currentoffset));
buffer.push(highByte(BF_CONFIG.currentoffset));
case MSPCodes.MSP_SET_FEATURE:
buffer.push(specificByte(FEATURES, 0));
buffer.push(specificByte(FEATURES, 1));
buffer.push(specificByte(FEATURES, 2));
buffer.push(specificByte(FEATURES, 3));
break;
case MSPCodes.MSP_SET_BOARD_ALIGNMENT:
buffer.push(specificByte(BOARD_ALIGNMENT.roll, 0));
buffer.push(specificByte(BOARD_ALIGNMENT.roll, 1));
buffer.push(specificByte(BOARD_ALIGNMENT.pitch, 0));
buffer.push(specificByte(BOARD_ALIGNMENT.pitch, 1));
buffer.push(specificByte(BOARD_ALIGNMENT.yaw, 0));
buffer.push(specificByte(BOARD_ALIGNMENT.yaw, 1));
break;
case MSPCodes.MSP_SET_CURRENT_METER_CONFIG:
buffer.push(specificByte(CURRENT_METER_CONFIG.scale, 0));
buffer.push(specificByte(CURRENT_METER_CONFIG.scale, 1));
buffer.push(specificByte(CURRENT_METER_CONFIG.offset, 0));
buffer.push(specificByte(CURRENT_METER_CONFIG.offset, 1));
buffer.push(CURRENT_METER_CONFIG.type);
buffer.push(specificByte(CURRENT_METER_CONFIG.capacity, 0));
buffer.push(specificByte(CURRENT_METER_CONFIG.capacity, 1));
break;
case MSPCodes.MSP_SET_VTX_CONFIG:
if (VTX_CONFIG.band > 0) {
buffer.push16(((VTX_CONFIG.band - 1) * 8) + (VTX_CONFIG.channel - 1));
@ -1589,13 +1534,6 @@ var mspHelper = (function (gui) {
buffer.push(0);
buffer.push(VTX_CONFIG.low_power_disarm);
break;
case MSPCodes.MSP_SET_PID:
for (i = 0; i < PIDs.length; i++) {
buffer.push(parseInt(PIDs[i][0]));
buffer.push(parseInt(PIDs[i][1]));
buffer.push(parseInt(PIDs[i][2]));
}
break;
case MSPCodes.MSP2_SET_PID:
for (i = 0; i < PIDs.length; i++) {
buffer.push(parseInt(PIDs[i][0]));
@ -1796,12 +1734,6 @@ var mspHelper = (function (gui) {
buffer.push(FAILSAFE_CONFIG.failsafe_min_distance_procedure);
break;
case MSPCodes.MSP_SET_TRANSPONDER_CONFIG:
for (i = 0; i < TRANSPONDER.data.length; i++) {
buffer.push(TRANSPONDER.data[i]);
}
break;
case MSPCodes.MSP_SET_CHANNEL_FORWARDING:
for (i = 0; i < SERVO_CONFIG.length; i++) {
var out = SERVO_CONFIG[i].indexOfChannelToForward;
@ -1812,24 +1744,6 @@ var mspHelper = (function (gui) {
}
break;
case MSPCodes.MSP_SET_CF_SERIAL_CONFIG:
for (i = 0; i < SERIAL_CONFIG.ports.length; i++) {
var serialPort = SERIAL_CONFIG.ports[i];
buffer.push(serialPort.identifier);
var functionMask = mspHelper.SERIAL_PORT_FUNCTIONSToMask(serialPort.functions);
buffer.push(specificByte(functionMask, 0));
buffer.push(specificByte(functionMask, 1));
var BAUD_RATES = mspHelper.BAUD_RATES_post1_6_3;
buffer.push(BAUD_RATES.indexOf(serialPort.msp_baudrate));
buffer.push(BAUD_RATES.indexOf(serialPort.sensors_baudrate));
buffer.push(BAUD_RATES.indexOf(serialPort.telemetry_baudrate));
buffer.push(BAUD_RATES.indexOf(serialPort.blackbox_baudrate));
}
break;
case MSPCodes.MSP2_SET_CF_SERIAL_CONFIG:
for (i = 0; i < SERIAL_CONFIG.ports.length; i++) {
var serialPort = SERIAL_CONFIG.ports[i];
@ -1967,16 +1881,14 @@ var mspHelper = (function (gui) {
buffer.push(lowByte(Math.round(CALIBRATION_DATA.opflow.Scale * 256)));
buffer.push(highByte(Math.round(CALIBRATION_DATA.opflow.Scale * 256)));
if (semver.gte(CONFIG.flightControllerVersion, "2.6.0")) {
buffer.push(lowByte(CALIBRATION_DATA.magGain.X));
buffer.push(highByte(CALIBRATION_DATA.magGain.X));
buffer.push(lowByte(CALIBRATION_DATA.magGain.X));
buffer.push(highByte(CALIBRATION_DATA.magGain.X));
buffer.push(lowByte(CALIBRATION_DATA.magGain.Y));
buffer.push(highByte(CALIBRATION_DATA.magGain.Y));
buffer.push(lowByte(CALIBRATION_DATA.magGain.Y));
buffer.push(highByte(CALIBRATION_DATA.magGain.Y));
buffer.push(lowByte(CALIBRATION_DATA.magGain.Z));
buffer.push(highByte(CALIBRATION_DATA.magGain.Z));
}
buffer.push(lowByte(CALIBRATION_DATA.magGain.Z));
buffer.push(highByte(CALIBRATION_DATA.magGain.Z));
break;
@ -2129,14 +2041,11 @@ var mspHelper = (function (gui) {
case MSPCodes.MSP_WP_MISSION_SAVE:
// buffer.push(0);
console.log(buffer);
buffer.push(0);
break;
case MSPCodes.MSP_WP_MISSION_LOAD:
// buffer.push(0);
console.log(buffer);
case MSPCodes.MSP_WP_MISSION_LOAD:
buffer.push(0);
break;
case MSPCodes.MSP2_INAV_SET_MIXER:
@ -2147,6 +2056,8 @@ var mspHelper = (function (gui) {
buffer.push(MIXER_CONFIG.hasFlaps);
buffer.push(lowByte(MIXER_CONFIG.appliedMixerPreset));
buffer.push(highByte(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:
@ -2193,17 +2104,18 @@ var mspHelper = (function (gui) {
};
self.sendBlackboxConfiguration = function (onDataCallback) {
var buffer = [];
var messageId = MSPCodes.MSP_SET_BLACKBOX_CONFIG;
buffer.push(BLACKBOX.blackboxDevice & 0xFF);
var buffer = [];
var messageId = MSPCodes.MSP_SET_BLACKBOX_CONFIG;
buffer.push(BLACKBOX.blackboxDevice & 0xFF);
messageId = MSPCodes.MSP2_SET_BLACKBOX_CONFIG;
buffer.push(lowByte(BLACKBOX.blackboxRateNum));
buffer.push(highByte(BLACKBOX.blackboxRateNum));
buffer.push(lowByte(BLACKBOX.blackboxRateDenom));
buffer.push(highByte(BLACKBOX.blackboxRateDenom));
buffer.push32(BLACKBOX.blackboxIncludeFlags);
//noinspection JSUnusedLocalSymbols
MSP.send_message(messageId, buffer, false, function (response) {
onDataCallback();
onDataCallback();
});
};
@ -2370,9 +2282,7 @@ var mspHelper = (function (gui) {
buffer.push(conditionIndex);
buffer.push(condition.getEnabled());
if (semver.gte(CONFIG.flightControllerVersion, "2.5.0")) {
buffer.push(condition.getActivatorId());
}
buffer.push(condition.getActivatorId());
buffer.push(condition.getOperation());
buffer.push(condition.getOperandAType());
buffer.push(specificByte(condition.getOperandAValue(), 0));
@ -2665,7 +2575,7 @@ var mspHelper = (function (gui) {
/*
ledDirectionLetters: ['n', 'e', 's', 'w', 'u', 'd'], // in LSB bit order
ledFunctionLetters: ['i', 'w', 'f', 'a', 't', 'r', 'c', 'g', 's', 'b', 'l'], // in LSB bit order
ledBaseFunctionLetters: ['c', 'f', 'a', 'l', 's', 'g', 'r'], // in LSB bit
ledBaseFunctionLetters: ['c', 'f', 'a', 'l', 's', 'g', 'r', 'h'], // in LSB bit
ledOverlayLetters: ['t', 'o', 'b', 'n', 'i', 'w'], // in LSB bit
*/
@ -2752,22 +2662,10 @@ var mspHelper = (function (gui) {
* Basic sending methods used for chaining purposes
*/
/**
* @deprecated
* @param callback
*/
self.loadMspIdent = function (callback) {
MSP.send_message(MSPCodes.MSP_IDENT, false, false, callback);
};
self.loadINAVPidConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_INAV_PID, false, false, callback);
};
self.loadLoopTime = function (callback) {
MSP.send_message(MSPCodes.MSP_LOOP_TIME, false, false, callback);
};
self.loadAdvancedConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_ADVANCED_CONFIG, false, false, callback);
};
@ -2796,12 +2694,16 @@ var mspHelper = (function (gui) {
MSP.send_message(MSPCodes.MSP_PIDNAMES, false, false, callback);
};
self.loadStatus = function (callback) {
MSP.send_message(MSPCodes.MSP_STATUS, false, false, callback);
self.loadFeatures = function (callback) {
MSP.send_message(MSPCodes.MSP_FEATURE, false, false, callback);
};
self.loadBfConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, callback);
self.loadBoardAlignment = function (callback) {
MSP.send_message(MSPCodes.MSP_BOARD_ALIGNMENT, false, false, callback);
};
self.loadCurrentMeterConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_CURRENT_METER_CONFIG, false, false, callback);
};
self.queryFcStatus = function (callback) {
@ -2821,7 +2723,7 @@ var mspHelper = (function (gui) {
};
self.loadBatteryConfig = function (callback) {
MSP.send_message(MSPCodes.MSPV2_BATTERY_CONFIG, false, false, callback);
MSP.send_message(MSPCodes.MSPV2_BATTERY_CONFIG, false, false, callback);
};
self.loadArmingConfig = function (callback) {
@ -2876,10 +2778,6 @@ var mspHelper = (function (gui) {
MSP.send_message(MSPCodes.MSP_SET_INAV_PID, mspHelper.crunch(MSPCodes.MSP_SET_INAV_PID), false, callback);
};
self.saveLooptimeConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_SET_LOOP_TIME, mspHelper.crunch(MSPCodes.MSP_SET_LOOP_TIME), false, callback);
};
self.saveAdvancedConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_SET_ADVANCED_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_ADVANCED_CONFIG), false, callback);
};
@ -2904,8 +2802,16 @@ var mspHelper = (function (gui) {
MSP.send_message(MSPCodes.MSP_SET_PID_ADVANCED, mspHelper.crunch(MSPCodes.MSP_SET_PID_ADVANCED), false, callback);
};
self.saveBfConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG), false, callback);
self.saveFeatures = function (callback) {
MSP.send_message(MSPCodes.MSP_SET_FEATURE, mspHelper.crunch(MSPCodes.MSP_SET_FEATURE), false, callback);
};
self.saveCurrentMeterConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_SET_CURRENT_METER_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_CURRENT_METER_CONFIG), false, callback);
};
self.saveBoardAlignment = function (callback) {
MSP.send_message(MSPCodes.MSP_SET_BOARD_ALIGNMENT, mspHelper.crunch(MSPCodes.MSP_SET_BOARD_ALIGNMENT), false, callback);
};
self.saveMisc = function (callback) {
@ -2981,7 +2887,7 @@ var mspHelper = (function (gui) {
};
self.saveFwConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_SET_FW_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FW_CONFIG), false, callback);
MSP.send_message(MSPCodes.MSP_SET_FW_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FW_CONFIG), false, callback);
};
self.getMissionInfo = function (callback) {
@ -3033,7 +2939,7 @@ var mspHelper = (function (gui) {
function nextSafehome() {
safehomeId++;
if (safehomeId < SAFEHOMES.getMaxSafehomeCount()-1) {
if (safehomeId < SAFEHOMES.getMaxSafehomeCount() - 1) {
MSP.send_message(MSPCodes.MSP2_INAV_SAFEHOME, [safehomeId], false, nextSafehome);
}
else {
@ -3048,7 +2954,7 @@ var mspHelper = (function (gui) {
function nextSendSafehome() {
safehomeId++;
if (safehomeId < SAFEHOMES.getMaxSafehomeCount()-1) {
if (safehomeId < SAFEHOMES.getMaxSafehomeCount() - 1) {
MSP.send_message(MSPCodes.MSP2_INAV_SET_SAFEHOME, SAFEHOMES.extractBuffer(safehomeId), false, nextSendSafehome);
}
else {
@ -3077,9 +2983,7 @@ var mspHelper = (function (gui) {
var setting = {};
// Discard setting name
if (semver.gte(CONFIG.apiVersion, "2.4.0")) {
result.data.readString();
}
result.data.readString();
// Discard PG ID
result.data.readU16();
@ -3107,7 +3011,7 @@ var mspHelper = (function (gui) {
for (var ii = setting.min; ii <= setting.max; ii++) {
values.push(result.data.readString());
}
setting.table = {values: values};
setting.table = { values: values };
}
SETTINGS[name] = setting;
return setting;
@ -3162,7 +3066,7 @@ var mspHelper = (function (gui) {
default:
throw "Unknown setting type " + setting.type;
}
return {setting: setting, value: value};
return { setting: setting, value: value };
});
});
};
@ -3251,8 +3155,8 @@ var mspHelper = (function (gui) {
MSP.send_message(MSPCodes.MSP_MOTOR, false, false, callback);
};
self.getCraftName = function(callback) {
MSP.send_message(MSPCodes.MSP_NAME, false, false, function(resp) {
self.getCraftName = function (callback) {
MSP.send_message(MSPCodes.MSP_NAME, false, false, function (resp) {
var name = resp.data.readString();
if (callback) {
callback(name);
@ -3260,7 +3164,7 @@ var mspHelper = (function (gui) {
});
};
self.setCraftName = function(name, callback) {
self.setCraftName = function (name, callback) {
var data = [];
name = name || "";
for (var ii = 0; ii < name.length; ii++) {
@ -3281,26 +3185,26 @@ var mspHelper = (function (gui) {
MSP.send_message(MSPCodes.MSP_VTX_CONFIG, false, false, callback);
};
self.saveVTXConfig = function(callback) {
self.saveVTXConfig = function (callback) {
MSP.send_message(MSPCodes.MSP_SET_VTX_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_VTX_CONFIG), false, callback);
};
self.loadBrakingConfig = function(callback) {
self.loadBrakingConfig = function (callback) {
MSP.send_message(MSPCodes.MSP2_INAV_MC_BRAKING, false, false, callback);
}
self.saveBrakingConfig = function(callback) {
self.saveBrakingConfig = function (callback) {
MSP.send_message(MSPCodes.MSP2_INAV_SET_MC_BRAKING, mspHelper.crunch(MSPCodes.MSP2_INAV_SET_MC_BRAKING), false, callback);
};
self.loadParameterGroups = function(callback) {
self.loadParameterGroups = function (callback) {
MSP.send_message(MSPCodes.MSP2_COMMON_PG_LIST, false, false, function (resp) {
var groups = [];
while (resp.data.offset < resp.data.byteLength) {
var id = resp.data.readU16();
var start = resp.data.readU16();
var end = resp.data.readU16();
groups.push({id: id, start: start, end: end});
groups.push({ id: id, start: start, end: end });
}
if (callback) {
callback(groups);
@ -3308,7 +3212,7 @@ var mspHelper = (function (gui) {
});
};
self.loadBrakingConfig = function(callback) {
self.loadBrakingConfig = function (callback) {
MSP.send_message(MSPCodes.MSP2_INAV_MC_BRAKING, false, false, callback);
}
@ -3317,19 +3221,11 @@ var mspHelper = (function (gui) {
};
self.loadGlobalVariablesStatus = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, "2.5.0")) {
MSP.send_message(MSPCodes.MSP2_INAV_GVAR_STATUS, false, false, callback);
} else {
callback();
}
MSP.send_message(MSPCodes.MSP2_INAV_GVAR_STATUS, false, false, callback);
};
self.loadProgrammingPidStatus = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, "2.6.0")) {
MSP.send_message(MSPCodes.MSP2_INAV_PROGRAMMING_PID_STATUS, false, false, callback);
} else {
callback();
}
MSP.send_message(MSPCodes.MSP2_INAV_PROGRAMMING_PID_STATUS, false, false, callback);
};
return self;

View file

@ -62,7 +62,7 @@ $(document).ready(function () {
} else {
helper.timeout.add('waiting_for_bootup', function waiting_for_bootup() {
MSP.send_message(MSPCodes.MSP_STATUS, false, false, function () {
MSP.send_message(MSPCodes.MSPV2_INAV_STATUS, false, false, function () {
//noinspection JSUnresolvedVariable
GUI.log(chrome.i18n.getMessage('deviceReady'));
//noinspection JSValidateTypes
@ -130,44 +130,52 @@ $(document).ready(function () {
helper.interval.killAll(['global_data_refresh', 'msp-load-update']);
helper.mspBalancedInterval.flush();
GUI.tab_switch_cleanup();
GUI.tab_switch_in_progress = false;
CONFIGURATOR.connectionValid = false;
GUI.connected_to = false;
GUI.allowedTabs = GUI.defaultAllowedTabsWhenDisconnected.slice();
/*
* Flush
*/
helper.mspQueue.flush();
helper.mspQueue.freeHardLock();
helper.mspQueue.freeSoftLock();
serial.disconnect(onClosed);
MSP.disconnect_cleanup();
// Reset various UI elements
$('span.i2c-error').text(0);
$('span.cycle-time').text(0);
$('span.cpu-load').text('');
// unlock port select & baud
$port.prop('disabled', false);
$baud.prop('disabled', false);
// reset connect / disconnect button
$('div.connect_controls a.connect').removeClass('active');
$('div.connect_controls a.connect_state').text(chrome.i18n.getMessage('connect'));
// reset active sensor indicators
sensor_status(0);
if (wasConnected) {
// detach listeners and remove element data
$('#content').empty();
if (CONFIGURATOR.cliActive) {
GUI.tab_switch_cleanup(finishDisconnect);
} else {
GUI.tab_switch_cleanup();
finishDisconnect();
}
$('#tabs .tab_landing a').click();
function finishDisconnect() {
GUI.tab_switch_in_progress = false;
CONFIGURATOR.connectionValid = false;
GUI.connected_to = false;
GUI.allowedTabs = GUI.defaultAllowedTabsWhenDisconnected.slice();
/*
* Flush
*/
helper.mspQueue.flush();
helper.mspQueue.freeHardLock();
helper.mspQueue.freeSoftLock();
serial.disconnect(onClosed);
MSP.disconnect_cleanup();
// Reset various UI elements
$('span.i2c-error').text(0);
$('span.cycle-time').text(0);
$('span.cpu-load').text('');
// unlock port select & baud
$port.prop('disabled', false);
$baud.prop('disabled', false);
// reset connect / disconnect button
$('div.connect_controls a.connect').removeClass('active');
$('div.connect_controls a.connect_state').text(chrome.i18n.getMessage('connect'));
// reset active sensor indicators
sensor_status(0);
if (wasConnected) {
// detach listeners and remove element data
$('#content').empty();
}
$('#tabs .tab_landing a').click();
}
}
$(this).data("clicks", !clicks);
@ -228,6 +236,13 @@ function onInvalidFirmwareVersion()
}
function onOpen(openInfo) {
if (FC.restartRequired) {
GUI_control.prototype.log("<span style='color: red; font-weight: bolder'><strong>" + chrome.i18n.getMessage("illegalStateRestartRequired") + "</strong></span>");
$('div.connect_controls a').click(); // disconnect
return;
}
if (openInfo) {
// update connected_to
GUI.connected_to = GUI.connecting_to;
@ -260,7 +275,12 @@ function onOpen(openInfo) {
if (!CONFIGURATOR.connectionValid) {
GUI.log(chrome.i18n.getMessage('noConfigurationReceived'));
$('div.connect_controls ').click(); // disconnect
helper.mspQueue.flush();
helper.mspQueue.freeHardLock();
helper.mspQueue.freeSoftLock();
serial.emptyOutputBuffer();
$('div.connect_controls a').click(); // disconnect
}
}, 10000);
@ -268,11 +288,15 @@ function onOpen(openInfo) {
// request configuration data. Start with MSPv1 and
// upgrade to MSPv2 if possible.
MSP.protocolVersion = MSP.constants.PROTOCOL_V1;
MSP.protocolVersion = MSP.constants.PROTOCOL_V2;
MSP.send_message(MSPCodes.MSP_API_VERSION, false, false, function () {
if (CONFIG.apiVersion && semver.gte(CONFIG.apiVersion, "2.0.0")) {
MSP.protocolVersion = MSP.constants.PROTOCOL_V2;
if (CONFIG.apiVersion === "0.0.0") {
GUI_control.prototype.log("<span style='color: red; font-weight: bolder'><strong>" + chrome.i18n.getMessage("illegalStateRestartRequired") + "</strong></span>");
FC.restartRequired = true;
return;
}
GUI.log(chrome.i18n.getMessage('apiVersionReceived', [CONFIG.apiVersion]));
MSP.send_message(MSPCodes.MSP_FC_VARIANT, false, false, function () {
@ -334,12 +358,8 @@ function onConnect() {
/*
* Init PIDs bank with a length that depends on the version
*/
let pidCount;
if (semver.gte(CONFIG.flightControllerVersion, "2.5.0")) {
pidCount = 11;
} else {
pidCount = 10;
}
let pidCount = 11;
for (let i = 0; i < pidCount; i++) {
PIDs.push(new Array(4));
}
@ -438,7 +458,7 @@ function sensor_status_hash(hw_status)
hw_status.gpsHwStatus +
hw_status.rangeHwStatus +
hw_status.speedHwStatus +
hw_status.flowHwStatus +
hw_status.flowHwStatus +
hw_status.imu2HwStatus;
}

View file

@ -72,6 +72,21 @@ let ServoMixerRuleCollection = function () {
return false;
};
self.getServoMixRuleFromTarget = function(wantedTarget) {
let returnTarget = null;
for (let ruleIndex in data) {
if (data.hasOwnProperty(ruleIndex)) {
if (data[ruleIndex].getTarget() == wantedTarget) {
returnTarget = data[ruleIndex];
break;
}
}
}
return returnTarget;
}
self.getNumberOfConfiguredServos = function () {
let count = 0;
for (let i = 0; i < self.getServoCount(); i ++) {
@ -99,5 +114,20 @@ let ServoMixerRuleCollection = function () {
});
}
self.getNextUnusedIndex = function() {
let nextTarget = 0;
for (let ruleIndex in data) {
if (data.hasOwnProperty(ruleIndex)) {
let target = data[ruleIndex].getTarget();
if (target > nextTarget) {
nextTarget = target;
}
}
}
return nextTarget+1;
}
return self;
};

View file

@ -12,6 +12,16 @@ var Settings = (function () {
var settingName = input.data('setting');
var inputUnit = input.data('unit');
if (globalSettings.showProfileParameters) {
if (FC.isBatteryProfileParameter(settingName)) {
input.css("background-color","#fef2d5");
}
if (FC.isControlProfileParameter(settingName)) {
input.css("background-color","#d5ebfe");
}
}
return mspHelper.getSetting(settingName).then(function (s) {
// Check if the input declares a parent
// to be hidden in case of the setting not being available.
@ -28,6 +38,8 @@ var Settings = (function () {
}
parent.show();
input.prop('title', 'CLI: ' + input.data('setting'));
if (input.prop('tagName') == 'SELECT' || s.setting.table) {
if (input.attr('type') == 'checkbox') {
input.prop('checked', s.value > 0);
@ -63,20 +75,20 @@ var Settings = (function () {
} else {
input.attr('step', "0.01");
}
input.attr('min', s.setting.min);
input.attr('max', s.setting.max);
input.val(s.value.toFixed(2));
} else {
var multiplier = parseFloat(input.data('setting-multiplier') || 1);
input.attr('type', 'number');
input.val((s.value / multiplier).toFixed(Math.log10(multiplier)));
if (s.setting.min) {
input.val((s.value / multiplier).toFixed(Math.log10(multiplier)));
input.attr('type', 'number');
if (typeof s.setting.min !== 'undefined' && s.setting.min !== null) {
input.attr('min', (s.setting.min / multiplier).toFixed(Math.log10(multiplier)));
}
if (s.setting.max) {
if (typeof s.setting.max !== 'undefined' && s.setting.max !== null) {
input.attr('max', (s.setting.max / multiplier).toFixed(Math.log10(multiplier)));
}
}
@ -112,19 +124,19 @@ var Settings = (function () {
const getUnitDisplayTypeValue = () => {
// Try and match the values
switch (configUnitType) {
case UnitType.imperial:
return 0;
break;
case UnitType.metric:
return 1;
break;
case UnitType.OSD: // Match the OSD value on the UI
return globalSettings.osdUnits;
break;
case UnitType.imperial:
return 0; // Imperial OSD Value
break;
case UnitType.metric:
return 1; // Metric + MPH OSD Value
break;
case UnitType.none:
default:
// Something went wrong
return -1;
break;
}
}
@ -134,67 +146,237 @@ var Settings = (function () {
const oldValue = element.val();
//display names for the units
const unitDisplayDames = {
// Misc
'us' : "uS",
'cw' : 'cW',
'percent' : '%',
'cmss' : 'cm/s/s',
// Time
'msec' : 'ms',
'dsec' : 'ds',
'sec' : 's',
// Angles
'deg' : '&deg;',
'decideg' : 'deci&deg;',
'decideg-lrg' : 'deci&deg;', // Decidegrees, but always converted to degrees by default
// Rotational speed
'degps' : '&deg; per second',
'decadegps' : 'deca&deg; per second',
// Temperature
'decidegc' : 'deci&deg;C',
'degc' : '&deg;C',
'degf' : '&deg;F',
// Speed
'cms' : 'cm/s',
'v-cms' : 'cm/s',
'ms' : 'm/s',
'kmh' : 'Km/h',
'mph' : 'mph',
'hftmin' : 'x100 ft/min',
'fts' : 'ft/s',
'kt' : 'Kt',
// Distance
'cm' : 'cm',
'm' : 'm',
'km' : 'Km',
'm-lrg' : 'm', // Metres, but converted to larger units
'ft' : 'ft',
'mi' : 'mi',
'nm' : 'NM'
}
// Ensure we can do conversions
if (configUnitType === UnitType.none || uiUnitValue === -1 || !inputUnit || !oldValue || !element) {
if (!inputUnit || !oldValue || !element) {
return;
}
// Used to convert between a value and a value matching the int
// unit display value. Eg 1 = Metric
// units. We use the OSD unit values here for easy
const conversionTable = {
1: {
'cm': { multiplier: 100, unitName: 'm' },
'cms': { multiplier: 27.77777777777778, unitName: 'Km/h' }
//this is used to get the factor in which we multiply
//to get the correct conversion, the first index is the from
//unit and the second is the too unit
//unitConversionTable[toUnit][fromUnit] -> factor
const unitRatioTable = {
'cm' : {
'm' : 100,
'ft' : 30.48
},
2: {
'cm': { multiplier: 100, unitName: 'm' },
},
4: {
'cms': { multiplier: 51.44444444444457, unitName: 'Kt' }
'm' : {
'm' : 1,
'ft' : 0.3048
},
default: {
'cm': { multiplier: 30.48, unitName: 'ft' },
'cms': { multiplier: 44.704, unitName: 'mph' },
'ms': { multiplier: 1000, unitName: 'sec' }
'm-lrg' : {
'km' : 1000,
'mi' : 1609.344,
'nm' : 1852
},
}
'cms' : { // Horizontal speed
'kmh' : 27.77777777777778,
'kt': 51.44444444444457,
'mph' : 44.704,
'ms' : 100
},
'v-cms' : { // Vertical speed
'ms' : 100,
'hftmin' : 50.8,
'fts' : 30.48
},
'msec' : {
'sec' : 1000
},
'dsec' : {
'sec' : 10
},
'decideg' : {
'deg' : 10
},
'decideg-lrg' : {
'deg' : 10
},
'decadegps' : {
'degps' : 0.1
},
'decidegc' : {
'degc' : 10,
'degf' : 'FAHREN'
},
};
// Small closure to try and get the multiplier
// needed from the conversion table
const getUnitMultiplier = () => {
if(conversionTable[uiUnitValue] && conversionTable[uiUnitValue][inputUnit]) {
return conversionTable[uiUnitValue][inputUnit];
//this holds which units get converted in which unit systems
const conversionTable = {
0: { //imperial
'cm' : 'ft',
'm' : 'ft',
'm-lrg' : 'mi',
'cms' : 'mph',
'v-cms' : 'fts',
'msec' : 'sec',
'dsec' : 'sec',
'decadegps' : 'degps',
'decideg' : 'deg',
'decideg-lrg' : 'deg',
'decidegc' : 'degf',
},
1: { //metric
'cm': 'm',
'm' : 'm',
'm-lrg' : 'km',
'cms' : 'kmh',
'v-cms' : 'ms',
'msec' : 'sec',
'dsec' : 'sec',
'decadegps' : 'degps',
'decideg' : 'deg',
'decideg-lrg' : 'deg',
'decidegc' : 'degc',
},
2: { //metric with MPH
'cm': 'm',
'm' : 'm',
'm-lrg' : 'km',
'cms' : 'mph',
'v-cms' : 'ms',
'decadegps' : 'degps',
'decideg' : 'deg',
'decideg-lrg' : 'deg',
'msec' : 'sec',
'dsec' : 'sec',
'decidegc' : 'degc',
},
3:{ //UK
'cm' : 'ft',
'm' : 'ft',
'm-lrg' : 'mi',
'cms' : 'mph',
'v-cms' : 'fts',
'decadegps' : 'degpd',
'decideg' : 'deg',
'decideg-lrg' : 'deg',
'msec' : 'sec',
'dsec' : 'sec',
'decidegc' : 'degc',
},
4: { //General aviation
'cm' : 'ft',
'm' : 'ft',
'm-lrg' : 'nm',
'cms': 'kt',
'v-cms' : 'hftmin',
'decadegps' : 'degps',
'decideg' : 'deg',
'decideg-lrg' : 'deg',
'msec' : 'sec',
'dsec' : 'sec',
'decidegc' : 'degc',
},
default: { //show base units
'decadegps' : 'degps',
'decideg-lrg' : 'deg',
}
return conversionTable['default'][inputUnit];
};
//this returns the factor in which to multiply to convert a unit
const getUnitMultiplier = () => {
let uiUnits = (uiUnitValue != -1) ? uiUnitValue : 'default';
if (conversionTable[uiUnits]){
const fromUnits = conversionTable[uiUnits];
if (fromUnits[inputUnit]){
const multiplier = unitRatioTable[inputUnit][fromUnits[inputUnit]];
return {'multiplier':multiplier, 'unitName':fromUnits[inputUnit]};
}
}
return {multiplier:1, unitName:inputUnit};
}
// Get the default multi obj or the custom
const multiObj = getUnitMultiplier();
if(!multiObj) {
return;
}
const multiplier = multiObj.multiplier;
const unitName = multiObj.unitName;
// Update the step, min, and max; as we have the multiplier here.
if (element.attr('type') == 'number') {
element.attr('step', ((multiplier != 1) ? '0.01' : '1'));
element.attr('min', (element.attr('min') / multiplier).toFixed(2));
element.attr('max', (element.attr('max') / multiplier).toFixed(2));
let step = element.attr('step') || 1;
let decimalPlaces = 0;
step = step / multiplier;
if (step < 1) {
decimalPlaces = step.toString().length - step.toString().indexOf(".") - 1;
if (parseInt(step.toString().slice(-1)) > 1 ) {
decimalPlaces--;
}
step = 1 / Math.pow(10, decimalPlaces);
}
element.attr('step', step.toFixed(decimalPlaces));
if (multiplier != 'FAHREN') {
element.attr('min', (element.attr('min') / multiplier).toFixed(decimalPlaces));
element.attr('max', (element.attr('max') / multiplier).toFixed(decimalPlaces));
}
}
// Update the input with a new formatted unit
const convertedValue = Number((oldValue / multiplier).toFixed(2));
const newValue = Number.isInteger(convertedValue) ? Math.round(convertedValue) : convertedValue;
let newValue = "";
if (multiplier == 'FAHREN') {
element.attr('min', toFahrenheit(element.attr('min')).toFixed(2));
element.attr('max', toFahrenheit(element.attr('max')).toFixed(2));
newValue = toFahrenheit(oldValue).toFixed(2);
} else {
const convertedValue = Number((oldValue / multiplier).toFixed(2));
newValue = Number.isInteger(convertedValue) ? Math.round(convertedValue) : convertedValue;
}
element.val(newValue);
element.data('setting-multiplier', multiplier);
// Now wrap the input in a display that shows the unit
element.wrap(`<div data-unit="${unitName}" class="unit_wrapper unit"></div>`);
element.wrap(`<div data-unit="${unitDisplayDames[unitName]}" class="unit_wrapper unit"></div>`);
function toFahrenheit(decidegC) {
return (decidegC / 10) * 1.8 + 32;
};
}
self.saveInput = function(input) {
@ -215,8 +397,13 @@ var Settings = (function () {
} else if(setting.type == 'string') {
value = input.val();
} else {
var multiplier = parseFloat(input.data('setting-multiplier') || 1);
value = parseFloat(input.val()) * multiplier;
var multiplier = input.data('setting-multiplier') || 1;
if (multiplier == 'FAHREN') {
value = Math.round(((parseFloat(input.val())-32) / 1.8) * 10);
} else {
multiplier = parseFloat(multiplier);
value = Math.round(parseFloat(input.val()) * multiplier);
}
}
return mspHelper.setSetting(settingName, value);
};

View file

@ -1,25 +0,0 @@
'use strict';
var helper = helper || {};
helper.task = (function () {
var publicScope = {},
privateScope = {};
privateScope.getStatusPullInterval = function () {
//TODO use serial connection speed to determine update interval
return 250;
};
publicScope.statusPullStart = function () {
helper.interval.add('status_pull', function () {
MSP.send_message(MSPCodes.MSP_STATUS, false, false, function () {
MSP.send_message(MSPCodes.MSP_SENSOR_STATUS);
});
}, privateScope.getStatusPullInterval(), true);
};
return publicScope;
})();