mirror of
https://github.com/betaflight/betaflight-configurator.git
synced 2025-07-16 12:55:14 +03:00
CF/BF - Update configurator for API 1.33.0.
This commit is contained in:
parent
57b9c58a22
commit
49100d29bd
24 changed files with 1168 additions and 1019 deletions
|
@ -667,14 +667,17 @@
|
||||||
"configurationThrottleMinimumCommandHelp": {
|
"configurationThrottleMinimumCommandHelp": {
|
||||||
"message": "This is the value that is sent to the ESCs when the craft is disarmed. Set this to a value that has the motors stopped (1000 for most ESCs)."
|
"message": "This is the value that is sent to the ESCs when the craft is disarmed. Set this to a value that has the motors stopped (1000 for most ESCs)."
|
||||||
},
|
},
|
||||||
"configurationBatteryVoltage": {
|
"configurationBattery": {
|
||||||
"message": "Battery Voltage"
|
"message": "Battery"
|
||||||
},
|
},
|
||||||
"configurationBatteryCurrent": {
|
"configurationVoltage": {
|
||||||
"message": "Battery Current"
|
"message": "Voltage"
|
||||||
},
|
},
|
||||||
"configurationBatteryMeterType": {
|
"configurationCurrent": {
|
||||||
"message": "Battery Meter Type"
|
"message": "Current"
|
||||||
|
},
|
||||||
|
"configurationBatteryVoltageMeterSource": {
|
||||||
|
"message": "Voltage Meter Source"
|
||||||
},
|
},
|
||||||
"configurationBatteryMinimum": {
|
"configurationBatteryMinimum": {
|
||||||
"message": "Minimum Cell Voltage"
|
"message": "Minimum Cell Voltage"
|
||||||
|
@ -688,8 +691,8 @@
|
||||||
"configurationBatteryScale": {
|
"configurationBatteryScale": {
|
||||||
"message": "Voltage Scale"
|
"message": "Voltage Scale"
|
||||||
},
|
},
|
||||||
"configurationCurrentMeterType": {
|
"configurationBatteryCurrentMeterSource": {
|
||||||
"message": "Current Meter Type"
|
"message": "Current Meter Source"
|
||||||
},
|
},
|
||||||
"configurationCurrent": {
|
"configurationCurrent": {
|
||||||
"message": "Current Sensor"
|
"message": "Current Sensor"
|
||||||
|
@ -700,11 +703,8 @@
|
||||||
"configurationCurrentOffset": {
|
"configurationCurrentOffset": {
|
||||||
"message": "Offset in millivolt steps"
|
"message": "Offset in millivolt steps"
|
||||||
},
|
},
|
||||||
"configurationBatteryMultiwiiCurrent": {
|
|
||||||
"message": "Enable support for legacy Multiwii MSP current output"
|
|
||||||
},
|
|
||||||
"configuration3d": {
|
"configuration3d": {
|
||||||
"message": "3D"
|
"message": "3D ESC/Motor Features"
|
||||||
},
|
},
|
||||||
"configuration3dDeadbandLow": {
|
"configuration3dDeadbandLow": {
|
||||||
"message": "3D Deadband Low"
|
"message": "3D Deadband Low"
|
||||||
|
@ -984,11 +984,23 @@
|
||||||
"receiverThrottleExpo": {
|
"receiverThrottleExpo": {
|
||||||
"message": "Throttle EXPO"
|
"message": "Throttle EXPO"
|
||||||
},
|
},
|
||||||
"receiverMidRc": {
|
"receiverStickMin": {
|
||||||
"message": "Center value for RC channels"
|
"message": "Stick Min"
|
||||||
},
|
},
|
||||||
"receiverMidRcHelp": {
|
"receiverHelpStickMin": {
|
||||||
"message": "This is the center value <span style=\"font-weight: bold\">for all RC channels</span>. Set this to the value that your transmitter sends when the stick is centered for a channel. To adjust the thrust at throttle mid position, change the 'Trottle MID' value on the PID Tuning tab."
|
"message": "The value (in us) used to determine if a stick is low."
|
||||||
|
},
|
||||||
|
"receiverStickCenter": {
|
||||||
|
"message": "Stick Center"
|
||||||
|
},
|
||||||
|
"receiverHelpStickCenter": {
|
||||||
|
"message": "The value (in us) used to determine if a stick is centered."
|
||||||
|
},
|
||||||
|
"receiverStickMax": {
|
||||||
|
"message": "Stick Max"
|
||||||
|
},
|
||||||
|
"receiverHelpStickMax": {
|
||||||
|
"message": "The value (in us) used to determine if a stick is high."
|
||||||
},
|
},
|
||||||
"receiverDeadband": {
|
"receiverDeadband": {
|
||||||
"message": "RC Deadband"
|
"message": "RC Deadband"
|
||||||
|
@ -996,11 +1008,17 @@
|
||||||
"receiverHelpDeadband": {
|
"receiverHelpDeadband": {
|
||||||
"message": "These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased if rc inputs twitch while idle."
|
"message": "These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased if rc inputs twitch while idle."
|
||||||
},
|
},
|
||||||
|
"receiverYawDeadband": {
|
||||||
|
"message": "Yaw Deadband"
|
||||||
|
},
|
||||||
"receiverHelpYawDeadband": {
|
"receiverHelpYawDeadband": {
|
||||||
"message": "These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased if rc inputs twitch while idle. <strong>This setting is for Yaw only.</strong>"
|
"message": "These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased if rc inputs twitch while idle. <strong>This setting is for Yaw only.</strong>"
|
||||||
},
|
},
|
||||||
"receiverYawDeadband": {
|
"recevier3dDeadbandThrottle": {
|
||||||
"message": "Yaw Deadband"
|
"message": "3D Throttle Deadband"
|
||||||
|
},
|
||||||
|
"receiverHelp3dDeadbandThrottle": {
|
||||||
|
"message": "These are values (in us). To widen the neutral zone increased the value. <strong>This setting is for 3D throttle only.</strong>"
|
||||||
},
|
},
|
||||||
"receiverChannelMap": {
|
"receiverChannelMap": {
|
||||||
"message": "Channel Map"
|
"message": "Channel Map"
|
||||||
|
@ -1948,10 +1966,13 @@
|
||||||
"pidTuningRatesTip": {
|
"pidTuningRatesTip": {
|
||||||
"message": "Play with the rates and see how those affect the stick curve"
|
"message": "Play with the rates and see how those affect the stick curve"
|
||||||
},
|
},
|
||||||
"configurationMisc": {
|
"configurationCamera": {
|
||||||
"message": "Misc"
|
"message": "Camera"
|
||||||
},
|
},
|
||||||
"configurationVesselName": {
|
"configurationPersonalization": {
|
||||||
|
"message": "Personalization"
|
||||||
|
},
|
||||||
|
"craftName": {
|
||||||
"message": "Craft name"
|
"message": "Craft name"
|
||||||
},
|
},
|
||||||
"configurationFpvCamAngleDegrees": {
|
"configurationFpvCamAngleDegrees": {
|
||||||
|
|
|
@ -19,7 +19,7 @@ function startApplication() {
|
||||||
// save connectionId in separate variable before createdWindow.contentWindow is destroyed
|
// save connectionId in separate variable before createdWindow.contentWindow is destroyed
|
||||||
var connectionId = createdWindow.contentWindow.serial.connectionId,
|
var connectionId = createdWindow.contentWindow.serial.connectionId,
|
||||||
valid_connection = createdWindow.contentWindow.CONFIGURATOR.connectionValid,
|
valid_connection = createdWindow.contentWindow.CONFIGURATOR.connectionValid,
|
||||||
mincommand = createdWindow.contentWindow.MISC.mincommand;
|
mincommand = createdWindow.contentWindow.MOTOR_CONFIG.mincommand;
|
||||||
|
|
||||||
if (connectionId && valid_connection) {
|
if (connectionId && valid_connection) {
|
||||||
// code below is handmade MSP message (without pretty JS wrapper), it behaves exactly like MSP.send_message
|
// code below is handmade MSP message (without pretty JS wrapper), it behaves exactly like MSP.send_message
|
||||||
|
|
|
@ -22,9 +22,7 @@ function configuration_backup(callback) {
|
||||||
];
|
];
|
||||||
|
|
||||||
function update_profile_specific_data_list() {
|
function update_profile_specific_data_list() {
|
||||||
if (semver.lt(CONFIG.apiVersion, "1.12.0")) {
|
if (semver.gt(CONFIG.apiVersion, "1.12.0")) {
|
||||||
profileSpecificData.push(MSPCodes.MSP_CHANNEL_FORWARDING);
|
|
||||||
} else {
|
|
||||||
profileSpecificData.push(MSPCodes.MSP_SERVO_MIX_RULES);
|
profileSpecificData.push(MSPCodes.MSP_SERVO_MIX_RULES);
|
||||||
}
|
}
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||||
|
@ -71,7 +69,7 @@ function configuration_backup(callback) {
|
||||||
});
|
});
|
||||||
|
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||||
configuration.profiles[fetchingProfile].RCdeadband = jQuery.extend(true, {}, RC_deadband);
|
configuration.profiles[fetchingProfile].RCdeadband = jQuery.extend(true, {}, RC_DEADBAND_CONFIG);
|
||||||
}
|
}
|
||||||
codeKey = 0;
|
codeKey = 0;
|
||||||
fetchingProfile++;
|
fetchingProfile++;
|
||||||
|
@ -89,9 +87,7 @@ function configuration_backup(callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
var uniqueData = [
|
var uniqueData = [
|
||||||
MSPCodes.MSP_MISC,
|
|
||||||
MSPCodes.MSP_RX_MAP,
|
MSPCodes.MSP_RX_MAP,
|
||||||
MSPCodes.MSP_BF_CONFIG,
|
|
||||||
MSPCodes.MSP_CF_SERIAL_CONFIG,
|
MSPCodes.MSP_CF_SERIAL_CONFIG,
|
||||||
MSPCodes.MSP_LED_STRIP_CONFIG,
|
MSPCodes.MSP_LED_STRIP_CONFIG,
|
||||||
MSPCodes.MSP_LED_COLORS
|
MSPCodes.MSP_LED_COLORS
|
||||||
|
@ -103,7 +99,7 @@ function configuration_backup(callback) {
|
||||||
uniqueData.push(MSPCodes.MSP_ARMING_CONFIG);
|
uniqueData.push(MSPCodes.MSP_ARMING_CONFIG);
|
||||||
}
|
}
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
||||||
uniqueData.push(MSPCodes.MSP_3D);
|
uniqueData.push(MSPCodes.MSP_MOTOR_3D_CONFIG);
|
||||||
}
|
}
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||||
uniqueData.push(MSPCodes.MSP_SENSOR_ALIGNMENT);
|
uniqueData.push(MSPCodes.MSP_SENSOR_ALIGNMENT);
|
||||||
|
@ -128,9 +124,7 @@ function configuration_backup(callback) {
|
||||||
fetch_unique_data_item();
|
fetch_unique_data_item();
|
||||||
});
|
});
|
||||||
} else {
|
} else {
|
||||||
configuration.MISC = jQuery.extend(true, {}, MISC);
|
|
||||||
configuration.RCMAP = jQuery.extend(true, [], RC_MAP);
|
configuration.RCMAP = jQuery.extend(true, [], RC_MAP);
|
||||||
configuration.BF_CONFIG = jQuery.extend(true, {}, BF_CONFIG);
|
|
||||||
configuration.SERIAL_CONFIG = jQuery.extend(true, {}, SERIAL_CONFIG);
|
configuration.SERIAL_CONFIG = jQuery.extend(true, {}, SERIAL_CONFIG);
|
||||||
configuration.LED_STRIP = jQuery.extend(true, [], LED_STRIP);
|
configuration.LED_STRIP = jQuery.extend(true, [], LED_STRIP);
|
||||||
configuration.LED_COLORS = jQuery.extend(true, [], LED_COLORS);
|
configuration.LED_COLORS = jQuery.extend(true, [], LED_COLORS);
|
||||||
|
@ -143,7 +137,7 @@ function configuration_backup(callback) {
|
||||||
configuration.ARMING_CONFIG = jQuery.extend(true, {}, ARMING_CONFIG);
|
configuration.ARMING_CONFIG = jQuery.extend(true, {}, ARMING_CONFIG);
|
||||||
}
|
}
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
||||||
configuration._3D = jQuery.extend(true, {}, _3D);
|
configuration.MOTOR_3D_CONFIG = jQuery.extend(true, {}, MOTOR_3D_CONFIG);
|
||||||
}
|
}
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||||
configuration.SENSOR_ALIGNMENT = jQuery.extend(true, {}, SENSOR_ALIGNMENT);
|
configuration.SENSOR_ALIGNMENT = jQuery.extend(true, {}, SENSOR_ALIGNMENT);
|
||||||
|
@ -151,6 +145,10 @@ function configuration_backup(callback) {
|
||||||
configuration.FAILSAFE_CONFIG = jQuery.extend(true, {}, FAILSAFE_CONFIG);
|
configuration.FAILSAFE_CONFIG = jQuery.extend(true, {}, FAILSAFE_CONFIG);
|
||||||
configuration.RXFAIL_CONFIG = jQuery.extend(true, [], RXFAIL_CONFIG);
|
configuration.RXFAIL_CONFIG = jQuery.extend(true, [], RXFAIL_CONFIG);
|
||||||
}
|
}
|
||||||
|
if (semver.gte(CONFIG.apiVersion, "1.33.0")) {
|
||||||
|
configuration.RSSI_CONFIG = jQuery.extend(true, {}, RSSI_CONFIG);
|
||||||
|
configuration.FEATURE_CONFIG = jQuery.extend(true, {}, FEATURE_CONFIG);
|
||||||
|
}
|
||||||
|
|
||||||
save();
|
save();
|
||||||
}
|
}
|
||||||
|
@ -163,13 +161,17 @@ function configuration_backup(callback) {
|
||||||
function save() {
|
function save() {
|
||||||
var chosenFileEntry = null;
|
var chosenFileEntry = null;
|
||||||
|
|
||||||
var prefix = 'betaflight_backup';
|
var prefix = CONFIG.flightControllerIdentifier + '_backup';
|
||||||
var suffix = 'json';
|
var suffix = 'json';
|
||||||
|
|
||||||
var filename = generateFilename(prefix, suffix);
|
var filename = generateFilename(prefix, suffix);
|
||||||
|
|
||||||
|
var accepts = [{
|
||||||
|
extensions: [suffix]
|
||||||
|
}];
|
||||||
|
|
||||||
// create or load the file
|
// create or load the file
|
||||||
chrome.fileSystem.chooseEntry({type: 'saveFile', suggestedName: filename, accepts: [{ extensions: [suffix] }]}, function (fileEntry) {
|
chrome.fileSystem.chooseEntry({type: 'saveFile', suggestedName: filename, accepts: accepts}, function (fileEntry) {
|
||||||
if (chrome.runtime.lastError) {
|
if (chrome.runtime.lastError) {
|
||||||
console.error(chrome.runtime.lastError.message);
|
console.error(chrome.runtime.lastError.message);
|
||||||
return;
|
return;
|
||||||
|
@ -328,7 +330,7 @@ function configuration_restore(callback) {
|
||||||
if (!compareVersions(migratedVersion, '0.59.1')) {
|
if (!compareVersions(migratedVersion, '0.59.1')) {
|
||||||
|
|
||||||
// variable was renamed
|
// variable was renamed
|
||||||
configuration.MISC.rssi_channel = configuration.MISC.rssi_aux_channel;
|
configuration.RSSI_CONFIG.channel = configuration.MISC.rssi_aux_channel;
|
||||||
configuration.MISC.rssi_aux_channel = undefined;
|
configuration.MISC.rssi_aux_channel = undefined;
|
||||||
|
|
||||||
migratedVersion = '0.59.1';
|
migratedVersion = '0.59.1';
|
||||||
|
@ -527,11 +529,11 @@ function configuration_restore(callback) {
|
||||||
if (compareVersions(migratedVersion, '0.66.0') && !compareVersions(configuration.apiVersion, '1.14.0')) {
|
if (compareVersions(migratedVersion, '0.66.0') && !compareVersions(configuration.apiVersion, '1.14.0')) {
|
||||||
// api 1.14 exposes 3D configuration
|
// api 1.14 exposes 3D configuration
|
||||||
|
|
||||||
if (configuration._3D == undefined) {
|
if (configuration.MOTOR_3D_CONFIG == undefined) {
|
||||||
configuration._3D = {
|
configuration.MOTOR_3D_CONFIG = {
|
||||||
deadband3d_low: 1406,
|
deadband3d_low: 1406,
|
||||||
deadband3d_high: 1514,
|
deadband3d_high: 1514,
|
||||||
neutral3d: 1460,
|
neutral: 1460,
|
||||||
deadband3d_throttle: 50
|
deadband3d_throttle: 50
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
@ -566,9 +568,9 @@ function configuration_restore(callback) {
|
||||||
configuration.RX_CONFIG = {
|
configuration.RX_CONFIG = {
|
||||||
serialrx_provider: 0,
|
serialrx_provider: 0,
|
||||||
spektrum_sat_bind: 0,
|
spektrum_sat_bind: 0,
|
||||||
midrc: 1500,
|
stick_center: 1500,
|
||||||
mincheck: 1100,
|
stick_min: 1100,
|
||||||
maxcheck: 1900,
|
stick_max: 1900,
|
||||||
rx_min_usec: 885,
|
rx_min_usec: 885,
|
||||||
rx_max_usec: 2115
|
rx_max_usec: 2115
|
||||||
};
|
};
|
||||||
|
@ -607,8 +609,8 @@ function configuration_restore(callback) {
|
||||||
|
|
||||||
if (compareVersions(migratedVersion, '1.2.0')) {
|
if (compareVersions(migratedVersion, '1.2.0')) {
|
||||||
// old version of the configurator incorrectly had a 'disabled' option for GPS SBAS mode.
|
// old version of the configurator incorrectly had a 'disabled' option for GPS SBAS mode.
|
||||||
if (MISC.gps_ubx_sbas < 0) {
|
if (GPS_CONFIG.ublox_sbas < 0) {
|
||||||
MISC.gps_ubx_sbas = 0;
|
GPS_CONFIG.ublox_sbas = 0;
|
||||||
}
|
}
|
||||||
migratedVersion = '1.2.0';
|
migratedVersion = '1.2.0';
|
||||||
|
|
||||||
|
@ -681,7 +683,7 @@ function configuration_restore(callback) {
|
||||||
SERVO_RULES = configuration.profiles[profile].ServoRules;
|
SERVO_RULES = configuration.profiles[profile].ServoRules;
|
||||||
MODE_RANGES = configuration.profiles[profile].ModeRanges;
|
MODE_RANGES = configuration.profiles[profile].ModeRanges;
|
||||||
ADJUSTMENT_RANGES = configuration.profiles[profile].AdjustmentRanges;
|
ADJUSTMENT_RANGES = configuration.profiles[profile].AdjustmentRanges;
|
||||||
RC_deadband = configuration.profiles[profile].RCdeadband;
|
RC_DEADBAND_CONFIG = configuration.profiles[profile].RCdeadband;
|
||||||
}
|
}
|
||||||
|
|
||||||
function upload_using_specific_commands() {
|
function upload_using_specific_commands() {
|
||||||
|
@ -729,9 +731,7 @@ function configuration_restore(callback) {
|
||||||
var codeKey = 0;
|
var codeKey = 0;
|
||||||
|
|
||||||
var uniqueData = [
|
var uniqueData = [
|
||||||
MSPCodes.MSP_SET_MISC,
|
|
||||||
MSPCodes.MSP_SET_RX_MAP,
|
MSPCodes.MSP_SET_RX_MAP,
|
||||||
MSPCodes.MSP_SET_BF_CONFIG,
|
|
||||||
MSPCodes.MSP_SET_CF_SERIAL_CONFIG
|
MSPCodes.MSP_SET_CF_SERIAL_CONFIG
|
||||||
];
|
];
|
||||||
|
|
||||||
|
@ -741,30 +741,41 @@ function configuration_restore(callback) {
|
||||||
uniqueData.push(MSPCodes.MSP_SET_ARMING_CONFIG);
|
uniqueData.push(MSPCodes.MSP_SET_ARMING_CONFIG);
|
||||||
}
|
}
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
||||||
uniqueData.push(MSPCodes.MSP_SET_3D);
|
uniqueData.push(MSPCodes.MSP_SET_MOTOR_3D_CONFIG);
|
||||||
}
|
}
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||||
uniqueData.push(MSPCodes.MSP_SET_SENSOR_ALIGNMENT);
|
uniqueData.push(MSPCodes.MSP_SET_SENSOR_ALIGNMENT);
|
||||||
uniqueData.push(MSPCodes.MSP_SET_RX_CONFIG);
|
uniqueData.push(MSPCodes.MSP_SET_RX_CONFIG);
|
||||||
uniqueData.push(MSPCodes.MSP_SET_FAILSAFE_CONFIG);
|
uniqueData.push(MSPCodes.MSP_SET_FAILSAFE_CONFIG);
|
||||||
}
|
}
|
||||||
|
if (semver.gte(CONFIG.apiVersion, "1.33.0")) {
|
||||||
|
uniqueData.push(MSPCodes.MSP_SET_FEATURE_CONFIG);
|
||||||
|
uniqueData.push(MSPCodes.MSP_SET_MOTOR_CONFIG);
|
||||||
|
uniqueData.push(MSPCodes.MSP_SET_GPS_CONFIG);
|
||||||
|
uniqueData.push(MSPCodes.MSP_SET_COMPASS_CONFIG);
|
||||||
|
uniqueData.push(MSPCodes.MSP_SET_RSSI_CONFIG);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_objects() {
|
function load_objects() {
|
||||||
MISC = configuration.MISC;
|
MISC = configuration.MISC;
|
||||||
RC_MAP = configuration.RCMAP;
|
RC_MAP = configuration.RCMAP;
|
||||||
BF_CONFIG = configuration.BF_CONFIG;
|
|
||||||
SERIAL_CONFIG = configuration.SERIAL_CONFIG;
|
SERIAL_CONFIG = configuration.SERIAL_CONFIG;
|
||||||
LED_STRIP = configuration.LED_STRIP;
|
LED_STRIP = configuration.LED_STRIP;
|
||||||
LED_COLORS = configuration.LED_COLORS;
|
LED_COLORS = configuration.LED_COLORS;
|
||||||
LED_MODE_COLORS = configuration.LED_MODE_COLORS;
|
LED_MODE_COLORS = configuration.LED_MODE_COLORS;
|
||||||
ARMING_CONFIG = configuration.ARMING_CONFIG;
|
ARMING_CONFIG = configuration.ARMING_CONFIG;
|
||||||
FC_CONFIG = configuration.FC_CONFIG;
|
FC_CONFIG = configuration.FC_CONFIG;
|
||||||
_3D = configuration._3D;
|
MOTOR_3D_CONFIG = configuration.MOTOR_3D_CONFIG;
|
||||||
SENSOR_ALIGNMENT = configuration.SENSOR_ALIGNMENT;
|
SENSOR_ALIGNMENT = configuration.SENSOR_ALIGNMENT;
|
||||||
RX_CONFIG = configuration.RX_CONFIG;
|
RX_CONFIG = configuration.RX_CONFIG;
|
||||||
FAILSAFE_CONFIG = configuration.FAILSAFE_CONFIG;
|
FAILSAFE_CONFIG = configuration.FAILSAFE_CONFIG;
|
||||||
RXFAIL_CONFIG = configuration.RXFAIL_CONFIG;
|
RXFAIL_CONFIG = configuration.RXFAIL_CONFIG;
|
||||||
|
FEATURE_CONFIG = configuration.FEATURE_CONFIG;
|
||||||
|
MOTOR_CONFIG = configuration.MOTOR_CONFIG;
|
||||||
|
GPS_CONFIG = configuration.GPS_CONFIG;
|
||||||
|
COMPASS_CONFIG = configuration.COMPASS_CONFIG;
|
||||||
|
RSSI_CONFIG = configuration.RSSI_CONFIG;
|
||||||
}
|
}
|
||||||
|
|
||||||
function send_unique_data_item() {
|
function send_unique_data_item() {
|
||||||
|
|
139
js/fc.js
139
js/fc.js
|
@ -1,8 +1,11 @@
|
||||||
'use strict';
|
'use strict';
|
||||||
|
|
||||||
// define all the global variables that are uses to hold FC state
|
// define all the global variables that are uses to hold FC state
|
||||||
var CONFIG;
|
var CONFIG; // FIXME rename to STATUS
|
||||||
var BF_CONFIG;
|
var FEATURE_CONFIG;
|
||||||
|
//var BF_CONFIG; // FIXME remove all references to this and delete it
|
||||||
|
var MIXER_CONFIG;
|
||||||
|
var BOARD_ALIGNMENT_CONFIG;
|
||||||
var LED_STRIP;
|
var LED_STRIP;
|
||||||
var LED_COLORS;
|
var LED_COLORS;
|
||||||
var LED_MODE_COLORS;
|
var LED_MODE_COLORS;
|
||||||
|
@ -24,15 +27,25 @@ var MOTOR_DATA;
|
||||||
var SERVO_DATA;
|
var SERVO_DATA;
|
||||||
var GPS_DATA;
|
var GPS_DATA;
|
||||||
var ANALOG;
|
var ANALOG;
|
||||||
|
var VOLTAGE_METERS;
|
||||||
|
var VOLTAGE_METER_CONFIGS;
|
||||||
|
var CURRENT_METERS;
|
||||||
|
var CURRENT_METER_CONFIGS;
|
||||||
|
var BATTERY_STATE;
|
||||||
|
var BATTERY_CONFIG;
|
||||||
var ARMING_CONFIG;
|
var ARMING_CONFIG;
|
||||||
var FC_CONFIG;
|
var FC_CONFIG;
|
||||||
var MISC;
|
var MOTOR_CONFIG;
|
||||||
var _3D;
|
var GPS_CONFIG;
|
||||||
|
var COMPASS_CONFIG;
|
||||||
|
var RSSI_CONFIG;
|
||||||
|
//var MISC; // FIXME remove all references to this and delete it
|
||||||
|
var MOTOR_3D_CONFIG;
|
||||||
var DATAFLASH;
|
var DATAFLASH;
|
||||||
var SDCARD;
|
var SDCARD;
|
||||||
var BLACKBOX;
|
var BLACKBOX;
|
||||||
var TRANSPONDER;
|
var TRANSPONDER;
|
||||||
var RC_deadband;
|
var RC_DEADBAND_CONFIG;
|
||||||
var SENSOR_ALIGNMENT;
|
var SENSOR_ALIGNMENT;
|
||||||
var RX_CONFIG;
|
var RX_CONFIG;
|
||||||
var FAILSAFE_CONFIG;
|
var FAILSAFE_CONFIG;
|
||||||
|
@ -65,18 +78,33 @@ var FC = {
|
||||||
rateProfile: 0
|
rateProfile: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
BF_CONFIG = {
|
FEATURE_CONFIG = {
|
||||||
mixerConfiguration: 0,
|
features: 0,
|
||||||
features: new Features(CONFIG),
|
|
||||||
board_align_roll: 0,
|
|
||||||
board_align_pitch: 0,
|
|
||||||
board_align_yaw: 0,
|
|
||||||
currentscale: 0,
|
|
||||||
currentoffset: 0,
|
|
||||||
currentmetertype: 0,
|
|
||||||
batterycapacity: 0,
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
MIXER_CONFIG = {
|
||||||
|
mixer: 0,
|
||||||
|
};
|
||||||
|
|
||||||
|
BOARD_ALIGNMENT_CONFIG = {
|
||||||
|
roll: 0,
|
||||||
|
pitch: 0,
|
||||||
|
yaw: 0,
|
||||||
|
};
|
||||||
|
|
||||||
|
// FIXME remove all references to this and delete it
|
||||||
|
// BF_CONFIG = {
|
||||||
|
// mixer: 0,
|
||||||
|
// features: new Features(CONFIG),
|
||||||
|
// board_align_roll: 0,
|
||||||
|
// board_align_pitch: 0,
|
||||||
|
// board_align_yaw: 0,
|
||||||
|
// currentscale: 0,
|
||||||
|
// currentoffset: 0,
|
||||||
|
// currentMeterSource: 0,
|
||||||
|
// batterycapacity: 0,
|
||||||
|
// };
|
||||||
|
|
||||||
LED_STRIP = [];
|
LED_STRIP = [];
|
||||||
LED_COLORS = [];
|
LED_COLORS = [];
|
||||||
LED_MODE_COLORS = [];
|
LED_MODE_COLORS = [];
|
||||||
|
@ -171,7 +199,22 @@ var FC = {
|
||||||
mAhdrawn: 0,
|
mAhdrawn: 0,
|
||||||
rssi: 0,
|
rssi: 0,
|
||||||
amperage: 0,
|
amperage: 0,
|
||||||
last_received_timestamp: Date.now()
|
last_received_timestamp: Date.now() // FIXME this code lies, it's never been received at this point
|
||||||
|
};
|
||||||
|
|
||||||
|
VOLTAGE_METERS = [];
|
||||||
|
VOLTAGE_METER_CONFIGS = [];
|
||||||
|
CURRENT_METERS = [];
|
||||||
|
CURRENT_METER_CONFIGS = [];
|
||||||
|
|
||||||
|
BATTERY_STATE = {};
|
||||||
|
BATTERY_CONFIG = {
|
||||||
|
vbatmincellvoltage: 0,
|
||||||
|
vbatmaxcellvoltage: 0,
|
||||||
|
vbatwarningcellvoltage: 0,
|
||||||
|
capacity: 0,
|
||||||
|
voltageMeterSource: 0,
|
||||||
|
currentMeterSource: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
ARMING_CONFIG = {
|
ARMING_CONFIG = {
|
||||||
|
@ -183,30 +226,49 @@ var FC = {
|
||||||
loopTime: 0
|
loopTime: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
MISC = {
|
MOTOR_CONFIG = {
|
||||||
minthrottle: 0,
|
minthrottle: 0,
|
||||||
maxthrottle: 0,
|
maxthrottle: 0,
|
||||||
mincommand: 0,
|
mincommand: 0,
|
||||||
failsafe_throttle: 0,
|
|
||||||
gps_type: 0,
|
|
||||||
gps_baudrate: 0,
|
|
||||||
gps_ubx_sbas: 0,
|
|
||||||
multiwiicurrentoutput: 0,
|
|
||||||
rssi_channel: 0,
|
|
||||||
placeholder2: 0,
|
|
||||||
mag_declination: 0, // not checked
|
|
||||||
vbatscale: 0,
|
|
||||||
vbatmincellvoltage: 0,
|
|
||||||
vbatmaxcellvoltage: 0,
|
|
||||||
vbatwarningcellvoltage: 0,
|
|
||||||
batterymetertype: 1, // 1=ADC, 2=ESC
|
|
||||||
};
|
};
|
||||||
|
|
||||||
_3D = {
|
GPS_CONFIG = {
|
||||||
|
provider: 0,
|
||||||
|
ublox_sbas: 0,
|
||||||
|
};
|
||||||
|
|
||||||
|
COMPASS_CONFIG = {
|
||||||
|
mag_declination: 0, // not checked
|
||||||
|
};
|
||||||
|
|
||||||
|
RSSI_CONFIG = {
|
||||||
|
channel: 0,
|
||||||
|
};
|
||||||
|
|
||||||
|
// FIXME remove all references to this and delete it
|
||||||
|
// MISC = {
|
||||||
|
// minthrottle: 0,
|
||||||
|
// maxthrottle: 0,
|
||||||
|
// mincommand: 0,
|
||||||
|
// failsafe_throttle: 0,
|
||||||
|
// gps_type: 0,
|
||||||
|
// gps_baudrate: 0,
|
||||||
|
// gps_ubx_sbas: 0,
|
||||||
|
// multiwiicurrentoutput: 0,
|
||||||
|
// rssi_channel: 0,
|
||||||
|
// placeholder2: 0,
|
||||||
|
// mag_declination: 0, // not checked
|
||||||
|
// vbatscale: 0,
|
||||||
|
// vbatmincellvoltage: 0,
|
||||||
|
// vbatmaxcellvoltage: 0,
|
||||||
|
// vbatwarningcellvoltage: 0,
|
||||||
|
// batterymetertype: 1, // 1=ADC, 2=ESC
|
||||||
|
// };
|
||||||
|
|
||||||
|
MOTOR_3D_CONFIG = {
|
||||||
deadband3d_low: 0,
|
deadband3d_low: 0,
|
||||||
deadband3d_high: 0,
|
deadband3d_high: 0,
|
||||||
neutral3d: 0,
|
neutral: 0,
|
||||||
deadband3d_throttle: 0
|
|
||||||
};
|
};
|
||||||
|
|
||||||
DATAFLASH = {
|
DATAFLASH = {
|
||||||
|
@ -237,10 +299,11 @@ var FC = {
|
||||||
data: []
|
data: []
|
||||||
};
|
};
|
||||||
|
|
||||||
RC_deadband = {
|
RC_DEADBAND_CONFIG = {
|
||||||
deadband: 0,
|
deadband: 0,
|
||||||
yaw_deadband: 0,
|
yaw_deadband: 0,
|
||||||
alt_hold_deadband: 0
|
alt_hold_deadband: 0,
|
||||||
|
deadband3d_throttle: 0
|
||||||
};
|
};
|
||||||
|
|
||||||
SENSOR_ALIGNMENT = {
|
SENSOR_ALIGNMENT = {
|
||||||
|
@ -296,9 +359,9 @@ var FC = {
|
||||||
|
|
||||||
RX_CONFIG = {
|
RX_CONFIG = {
|
||||||
serialrx_provider: 0,
|
serialrx_provider: 0,
|
||||||
maxcheck: 0,
|
stick_max: 0,
|
||||||
midrc: 0,
|
stick_center: 0,
|
||||||
mincheck: 0,
|
stick_min: 0,
|
||||||
spektrum_sat_bind: 0,
|
spektrum_sat_bind: 0,
|
||||||
rx_min_usec: 0,
|
rx_min_usec: 0,
|
||||||
rx_max_usec: 0,
|
rx_max_usec: 0,
|
||||||
|
|
|
@ -47,7 +47,7 @@ var Model = function (wrapper, canvas) {
|
||||||
this.renderer.setSize(this.wrapper.width() * 2, this.wrapper.height() * 2);
|
this.renderer.setSize(this.wrapper.width() * 2, this.wrapper.height() * 2);
|
||||||
|
|
||||||
// load the model including materials
|
// load the model including materials
|
||||||
var model_file = useWebGLRenderer ? mixerList[BF_CONFIG.mixerConfiguration - 1].model : 'fallback';
|
var model_file = useWebGLRenderer ? mixerList[MIXER_CONFIG.mixer - 1].model : 'fallback';
|
||||||
|
|
||||||
// Temporary workaround for 'custom' model until akfreak's custom model is merged.
|
// Temporary workaround for 'custom' model until akfreak's custom model is merged.
|
||||||
if (model_file == 'custom') { model_file = 'fallback'; }
|
if (model_file == 'custom') { model_file = 'fallback'; }
|
||||||
|
|
|
@ -148,6 +148,9 @@ var MSP = {
|
||||||
this.listeners = [];
|
this.listeners = [];
|
||||||
},
|
},
|
||||||
send_message: function (code, data, callback_sent, callback_msp, callback_onerror) {
|
send_message: function (code, data, callback_sent, callback_msp, callback_onerror) {
|
||||||
|
if (code === undefined) {
|
||||||
|
debugger;
|
||||||
|
}
|
||||||
var bufferOut,
|
var bufferOut,
|
||||||
bufView;
|
bufView;
|
||||||
|
|
||||||
|
|
|
@ -11,21 +11,26 @@ var MSPCodes = {
|
||||||
MSP_NAME: 10,
|
MSP_NAME: 10,
|
||||||
MSP_SET_NAME: 11,
|
MSP_SET_NAME: 11,
|
||||||
|
|
||||||
MSP_CHANNEL_FORWARDING: 32,
|
MSP_BATTERY_CONFIG: 32,
|
||||||
MSP_SET_CHANNEL_FORWARDING: 33,
|
MSP_SET_BATTERY_CONFIG: 33,
|
||||||
MSP_MODE_RANGES: 34,
|
MSP_MODE_RANGES: 34,
|
||||||
MSP_SET_MODE_RANGE: 35,
|
MSP_SET_MODE_RANGE: 35,
|
||||||
|
MSP_FEATURE_CONFIG: 36,
|
||||||
|
MSP_SET_FEATURE_CONFIG: 37,
|
||||||
|
MSP_BOARD_ALIGNMENT_CONFIG: 38,
|
||||||
|
MSP_SET_BOARD_ALIGNMENT_CONFIG: 39,
|
||||||
MSP_CURRENT_METER_CONFIG: 40,
|
MSP_CURRENT_METER_CONFIG: 40,
|
||||||
MSP_SET_CURRENT_METER_CONFIG: 41,
|
MSP_SET_CURRENT_METER_CONFIG: 41,
|
||||||
|
MSP_MIXER_CONFIG: 42,
|
||||||
|
MSP_SET_MIXER_CONFIG: 43,
|
||||||
MSP_RX_CONFIG: 44,
|
MSP_RX_CONFIG: 44,
|
||||||
MSP_SET_RX_CONFIG: 45,
|
MSP_SET_RX_CONFIG: 45,
|
||||||
MSP_LED_COLORS: 46,
|
MSP_LED_COLORS: 46,
|
||||||
MSP_SET_LED_COLORS: 47,
|
MSP_SET_LED_COLORS: 47,
|
||||||
MSP_LED_STRIP_CONFIG: 48,
|
MSP_LED_STRIP_CONFIG: 48,
|
||||||
MSP_SET_LED_STRIP_CONFIG: 49,
|
MSP_SET_LED_STRIP_CONFIG: 49,
|
||||||
|
MSP_RSSI_CONFIG: 50,
|
||||||
|
MSP_SET_RSSI_CONFIG: 51,
|
||||||
MSP_ADJUSTMENT_RANGES: 52,
|
MSP_ADJUSTMENT_RANGES: 52,
|
||||||
MSP_SET_ADJUSTMENT_RANGE: 53,
|
MSP_SET_ADJUSTMENT_RANGE: 53,
|
||||||
MSP_CF_SERIAL_CONFIG: 54,
|
MSP_CF_SERIAL_CONFIG: 54,
|
||||||
|
@ -39,8 +44,8 @@ var MSPCodes = {
|
||||||
MSP_SET_ARMING_CONFIG: 62,
|
MSP_SET_ARMING_CONFIG: 62,
|
||||||
MSP_RX_MAP: 64,
|
MSP_RX_MAP: 64,
|
||||||
MSP_SET_RX_MAP: 65,
|
MSP_SET_RX_MAP: 65,
|
||||||
MSP_BF_CONFIG: 66,
|
//MSP_BF_CONFIG: 66, // DEPRECATED
|
||||||
MSP_SET_BF_CONFIG: 67,
|
//MSP_SET_BF_CONFIG: 67, // DEPRECATED
|
||||||
MSP_SET_REBOOT: 68,
|
MSP_SET_REBOOT: 68,
|
||||||
MSP_BF_BUILD_INFO: 69, // Not used
|
MSP_BF_BUILD_INFO: 69, // Not used
|
||||||
MSP_DATAFLASH_SUMMARY: 70,
|
MSP_DATAFLASH_SUMMARY: 70,
|
||||||
|
@ -71,9 +76,9 @@ var MSPCodes = {
|
||||||
MSP_SET_PID_ADVANCED: 95,
|
MSP_SET_PID_ADVANCED: 95,
|
||||||
MSP_SENSOR_CONFIG: 96,
|
MSP_SENSOR_CONFIG: 96,
|
||||||
MSP_SET_SENSOR_CONFIG: 97,
|
MSP_SET_SENSOR_CONFIG: 97,
|
||||||
// MSP_SPECIAL_PARAMETERS: 98, removed
|
//MSP_SPECIAL_PARAMETERS: 98, // DEPRECATED
|
||||||
//MSP_SET_SPECIAL_PARAMETERS: 99, removed
|
//MSP_SET_SPECIAL_PARAMETERS: 99, // DEPRECATED
|
||||||
MSP_IDENT: 100, // Not used
|
//MSP_IDENT: 100, // DEPRECTED
|
||||||
MSP_STATUS: 101,
|
MSP_STATUS: 101,
|
||||||
MSP_RAW_IMU: 102,
|
MSP_RAW_IMU: 102,
|
||||||
MSP_SERVO: 103,
|
MSP_SERVO: 103,
|
||||||
|
@ -86,19 +91,25 @@ var MSPCodes = {
|
||||||
MSP_ANALOG: 110,
|
MSP_ANALOG: 110,
|
||||||
MSP_RC_TUNING: 111,
|
MSP_RC_TUNING: 111,
|
||||||
MSP_PID: 112,
|
MSP_PID: 112,
|
||||||
MSP_BOX: 113, // Not used
|
//MSP_BOX: 113, // DEPRECATED
|
||||||
MSP_MISC: 114,
|
//MSP_MISC: 114, // DEPRECATED
|
||||||
MSP_MOTOR_PINS: 115, // Not used
|
|
||||||
MSP_BOXNAMES: 116,
|
MSP_BOXNAMES: 116,
|
||||||
MSP_PIDNAMES: 117,
|
MSP_PIDNAMES: 117,
|
||||||
MSP_WP: 118, // Not used
|
MSP_WP: 118, // Not used
|
||||||
MSP_BOXIDS: 119,
|
MSP_BOXIDS: 119,
|
||||||
MSP_SERVO_CONFIGURATIONS: 120,
|
MSP_SERVO_CONFIGURATIONS: 120,
|
||||||
MSP_3D: 124,
|
MSP_MOTOR_3D_CONFIG: 124,
|
||||||
MSP_RC_DEADBAND: 125,
|
MSP_RC_DEADBAND: 125,
|
||||||
MSP_SENSOR_ALIGNMENT: 126,
|
MSP_SENSOR_ALIGNMENT: 126,
|
||||||
MSP_LED_STRIP_MODECOLOR: 127,
|
MSP_LED_STRIP_MODECOLOR: 127,
|
||||||
|
|
||||||
|
MSP_VOLTAGE_METERS: 128,
|
||||||
|
MSP_CURRENT_METERS: 129,
|
||||||
|
MSP_BATTERY_STATE: 130,
|
||||||
|
MSP_MOTOR_CONFIG: 131,
|
||||||
|
MSP_GPS_CONFIG: 132,
|
||||||
|
MSP_COMPASS_CONFIG: 133,
|
||||||
|
|
||||||
MSP_STATUS_EX: 150,
|
MSP_STATUS_EX: 150,
|
||||||
|
|
||||||
MSP_UID: 160,
|
MSP_UID: 160,
|
||||||
|
@ -109,22 +120,25 @@ var MSPCodes = {
|
||||||
MSP_SET_RAW_RC: 200,
|
MSP_SET_RAW_RC: 200,
|
||||||
MSP_SET_RAW_GPS: 201, // Not used
|
MSP_SET_RAW_GPS: 201, // Not used
|
||||||
MSP_SET_PID: 202,
|
MSP_SET_PID: 202,
|
||||||
MSP_SET_BOX: 203,
|
//MSP_SET_BOX: 203, // DEPRECATED
|
||||||
MSP_SET_RC_TUNING: 204,
|
MSP_SET_RC_TUNING: 204,
|
||||||
MSP_ACC_CALIBRATION: 205,
|
MSP_ACC_CALIBRATION: 205,
|
||||||
MSP_MAG_CALIBRATION: 206,
|
MSP_MAG_CALIBRATION: 206,
|
||||||
MSP_SET_MISC: 207,
|
//MSP_SET_MISC: 207, // DEPRECATED
|
||||||
MSP_RESET_CONF: 208,
|
MSP_RESET_CONF: 208,
|
||||||
MSP_SET_WP: 209, // Not used
|
MSP_SET_WP: 209, // Not used
|
||||||
MSP_SELECT_SETTING: 210,
|
MSP_SELECT_SETTING: 210,
|
||||||
MSP_SET_HEAD: 211, // Not used
|
MSP_SET_HEADING: 211, // Not used
|
||||||
MSP_SET_SERVO_CONFIGURATION: 212,
|
MSP_SET_SERVO_CONFIGURATION: 212,
|
||||||
MSP_SET_MOTOR: 214,
|
MSP_SET_MOTOR: 214,
|
||||||
MSP_SET_3D: 217,
|
MSP_SET_MOTOR_3D_CONFIG: 217,
|
||||||
MSP_SET_RC_DEADBAND: 218,
|
MSP_SET_RC_DEADBAND: 218,
|
||||||
MSP_SET_RESET_CURR_PID: 219,
|
MSP_SET_RESET_CURR_PID: 219,
|
||||||
MSP_SET_SENSOR_ALIGNMENT: 220,
|
MSP_SET_SENSOR_ALIGNMENT: 220,
|
||||||
MSP_SET_LED_STRIP_MODECOLOR: 221,
|
MSP_SET_LED_STRIP_MODECOLOR: 221,
|
||||||
|
MSP_SET_MOTOR_CONFIG: 222,
|
||||||
|
MSP_SET_GPS_CONFIG: 223,
|
||||||
|
MSP_SET_COMPASS_CONFIG: 224,
|
||||||
|
|
||||||
MSP_SET_ACC_TRIM: 239,
|
MSP_SET_ACC_TRIM: 239,
|
||||||
MSP_ACC_TRIM: 240,
|
MSP_ACC_TRIM: 240,
|
||||||
|
|
|
@ -52,6 +52,9 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
||||||
|
|
||||||
var data = dataHandler.dataView; // DataView (allowing us to view arrayBuffer as struct/union)
|
var data = dataHandler.dataView; // DataView (allowing us to view arrayBuffer as struct/union)
|
||||||
var code = dataHandler.code;
|
var code = dataHandler.code;
|
||||||
|
if (code === 0) {
|
||||||
|
debugger;
|
||||||
|
}
|
||||||
var crcError = dataHandler.crcError;
|
var crcError = dataHandler.crcError;
|
||||||
if (!crcError) {
|
if (!crcError) {
|
||||||
if (!dataHandler.unsupported) switch (code) {
|
if (!dataHandler.unsupported) switch (code) {
|
||||||
|
@ -154,6 +157,90 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
||||||
ANALOG.rssi = data.readU16(); // 0-1023
|
ANALOG.rssi = data.readU16(); // 0-1023
|
||||||
ANALOG.amperage = data.read16() / 100; // A
|
ANALOG.amperage = data.read16() / 100; // A
|
||||||
ANALOG.last_received_timestamp = Date.now();
|
ANALOG.last_received_timestamp = Date.now();
|
||||||
|
break;
|
||||||
|
// case MSPCodes.MSP_VOLTAGE_METERS:
|
||||||
|
// VOLTAGE_METERS = [];
|
||||||
|
// for (var i = 0; i < (message_length); i++) {
|
||||||
|
// var voltageMeter = {};
|
||||||
|
// voltageMeter.voltage = data.readU8() / 10.0;
|
||||||
|
//
|
||||||
|
// VOLTAGE_METERS.push(voltageMeter)
|
||||||
|
// }
|
||||||
|
// break;
|
||||||
|
// case MSPCodes.MSP_CURRENT_METERS:
|
||||||
|
// CURRENT_METERS = [];
|
||||||
|
// for (var i = 0; i < (message_length / 6); i++) {
|
||||||
|
// var amperageMeter = {};
|
||||||
|
// amperageMeter.amperage = data.read16() / 1000; // A
|
||||||
|
// offset += 2;
|
||||||
|
// amperageMeter.mAhDrawn = data.readU32(); // A
|
||||||
|
// offset += 4;
|
||||||
|
//
|
||||||
|
// CURRENT_METERS.push(amperageMeter);
|
||||||
|
// }
|
||||||
|
// break;
|
||||||
|
case MSPCodes.MSP_BATTERY_STATE:
|
||||||
|
BATTERY_STATE.cellCount = data.readU8();
|
||||||
|
BATTERY_STATE.capacity = data.readU16(); // mAh
|
||||||
|
|
||||||
|
BATTERY_STATE.voltage = data.readU8() / 10.0; // V
|
||||||
|
BATTERY_STATE.mAhDrawn = data.readU16(); // mAh
|
||||||
|
BATTERY_STATE.amperage = data.readU16() / 100; // A
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MSPCodes.MSP_VOLTAGE_METER_CONFIG:
|
||||||
|
VOLTAGE_METER_CONFIGS = [];
|
||||||
|
var voltage_meter_count = data.readU8();
|
||||||
|
|
||||||
|
for (var i = 0; i < voltage_meter_count; i++) {
|
||||||
|
var subframe_length = data.readU8();
|
||||||
|
if (subframe_length != 5) {
|
||||||
|
for (var j = 0; j < subframe_length; j++) {
|
||||||
|
data.readU8();
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
var voltageMeterConfig = {};
|
||||||
|
voltageMeterConfig.id = data.readU8();
|
||||||
|
voltageMeterConfig.sensorType = data.readU8();
|
||||||
|
voltageMeterConfig.vbatscale = data.readU8();
|
||||||
|
voltageMeterConfig.vbatresdivval = data.readU8();
|
||||||
|
voltageMeterConfig.vbatresdivmultiplier = data.readU8();
|
||||||
|
|
||||||
|
VOLTAGE_METER_CONFIGS.push(voltageMeterConfig);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case MSPCodes.MSP_CURRENT_METER_CONFIG:
|
||||||
|
var offset = 0;
|
||||||
|
CURRENT_METER_CONFIGS = [];
|
||||||
|
var current_meter_count = data.readU8();
|
||||||
|
for (var i = 0; i < current_meter_count; i++) {
|
||||||
|
var currentMeterConfig = {};
|
||||||
|
var subframe_length = data.readU8();
|
||||||
|
|
||||||
|
if (subframe_length != 6) {
|
||||||
|
for (var j = 0; j < subframe_length; j++) {
|
||||||
|
data.readU8();
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
currentMeterConfig.id = data.readU8();
|
||||||
|
currentMeterConfig.sensorType = data.readU8();
|
||||||
|
currentMeterConfig.scale = data.readU16();
|
||||||
|
currentMeterConfig.offset = data.readU16();
|
||||||
|
|
||||||
|
CURRENT_METER_CONFIGS.push(currentMeterConfig);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MSPCodes.MSP_BATTERY_CONFIG:
|
||||||
|
BATTERY_CONFIG.vbatmincellvoltage = data.readU8() / 10; // 10-50
|
||||||
|
BATTERY_CONFIG.vbatmaxcellvoltage = data.readU8() / 10; // 10-50
|
||||||
|
BATTERY_CONFIG.vbatwarningcellvoltage = data.readU8() / 10; // 10-50
|
||||||
|
BATTERY_CONFIG.capacity = data.readU16();
|
||||||
|
BATTERY_CONFIG.voltageMeterSource = data.readU8();
|
||||||
|
BATTERY_CONFIG.currentMeterSource = data.readU8();
|
||||||
|
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_RC_TUNING:
|
case MSPCodes.MSP_RC_TUNING:
|
||||||
RC_tuning.RC_RATE = parseFloat((data.readU8() / 100).toFixed(2));
|
RC_tuning.RC_RATE = parseFloat((data.readU8() / 100).toFixed(2));
|
||||||
|
@ -203,53 +290,47 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
||||||
ARMING_CONFIG.disarm_kill_switch = data.readU8();
|
ARMING_CONFIG.disarm_kill_switch = data.readU8();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_LOOP_TIME:
|
case MSPCodes.MSP_MOTOR_CONFIG:
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
MOTOR_CONFIG.minthrottle = data.readU16(); // 0-2000
|
||||||
FC_CONFIG.loopTime = data.readU16();
|
MOTOR_CONFIG.maxthrottle = data.readU16(); // 0-2000
|
||||||
}
|
MOTOR_CONFIG.mincommand = data.readU16(); // 0-2000
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_MISC: // 22 bytes
|
case MSPCodes.MSP_COMPASS_CONFIG:
|
||||||
RX_CONFIG.midrc = data.readU16();
|
COMPASS_CONFIG.mag_declination = data.read16() / 100; // -18000-18000
|
||||||
MISC.minthrottle = data.readU16(); // 0-2000
|
|
||||||
MISC.maxthrottle = data.readU16(); // 0-2000
|
|
||||||
MISC.mincommand = data.readU16(); // 0-2000
|
|
||||||
MISC.failsafe_throttle = data.readU16(); // 1000-2000
|
|
||||||
MISC.gps_type = data.readU8();
|
|
||||||
MISC.gps_baudrate = data.readU8();
|
|
||||||
MISC.gps_ubx_sbas = data.readU8();
|
|
||||||
MISC.multiwiicurrentoutput = data.readU8();
|
|
||||||
MISC.rssi_channel = data.readU8();
|
|
||||||
MISC.placeholder2 = data.readU8();
|
|
||||||
if (semver.lt(CONFIG.apiVersion, "1.18.0"))
|
|
||||||
MISC.mag_declination = data.read16() / 10; // -1800-1800
|
|
||||||
else
|
|
||||||
MISC.mag_declination = data.read16() / 100; // -18000-18000
|
|
||||||
MISC.vbatscale = data.readU8(); // 10-200
|
|
||||||
MISC.vbatmincellvoltage = data.readU8() / 10; // 10-50
|
|
||||||
MISC.vbatmaxcellvoltage = data.readU8() / 10; // 10-50
|
|
||||||
MISC.vbatwarningcellvoltage = data.readU8() / 10; // 10-50
|
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_VOLTAGE_METER_CONFIG:
|
case MSPCodes.MSP_GPS_CONFIG:
|
||||||
MISC.vbatscale = data.readU8(); // 10-200
|
GPS_CONFIG.provider = data.readU8();
|
||||||
MISC.vbatmincellvoltage = data.readU8() / 10; // 10-50
|
GPS_CONFIG.ublox_sbas = data.readU8();
|
||||||
MISC.vbatmaxcellvoltage = data.readU8() / 10; // 10-50
|
|
||||||
MISC.vbatwarningcellvoltage = data.readU8() / 10; // 10-50
|
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.23.0")) {
|
|
||||||
MISC.batterymetertype = data.readU8();
|
|
||||||
}
|
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_CURRENT_METER_CONFIG:
|
case MSPCodes.MSP_RSSI_CONFIG:
|
||||||
BF_CONFIG.currentscale = data.read16();
|
RSSI_CONFIG.channel = data.readU8();
|
||||||
BF_CONFIG.currentoffset = data.read16();
|
|
||||||
BF_CONFIG.currentmetertype = data.readU8();
|
|
||||||
BF_CONFIG.batterycapacity = data.readU16();
|
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_3D:
|
// case MSPCodes.MSP_MISC:
|
||||||
_3D.deadband3d_low = data.readU16();
|
// RX_CONFIG.stick_center = data.readU16();
|
||||||
_3D.deadband3d_high = data.readU16();
|
// MOTOR_CONFIG.minthrottle = data.readU16(); // 0-2000
|
||||||
_3D.neutral3d = data.readU16();
|
// MOTOR_CONFIG.maxthrottle = data.readU16(); // 0-2000
|
||||||
|
// MOTOR_CONFIG.mincommand = data.readU16(); // 0-2000
|
||||||
|
// MISC.failsafe_throttle = data.readU16(); // 1000-2000
|
||||||
|
// GPS_CONFIG.provider = data.readU8();
|
||||||
|
// GPS_CONFIG.baudrate = data.readU8();
|
||||||
|
// GPS_CONFIG.ublox_sbas = data.readU8();
|
||||||
|
// MISC.multiwiicurrentoutput = data.readU8();
|
||||||
|
// MISC.placeholder2 = data.readU8();
|
||||||
|
// if (semver.lt(CONFIG.apiVersion, "1.18.0"))
|
||||||
|
// COMPASS_CONFIG.mag_declination = data.read16() / 10; // -1800-1800
|
||||||
|
// else
|
||||||
|
// COMPASS_CONFIG.mag_declination = data.read16() / 100; // -18000-18000
|
||||||
|
// MISC.vbatscale = data.readU8(); // 10-200
|
||||||
|
// BATTERY_CONFIG.vbatmincellvoltage = data.readU8() / 10; // 10-50
|
||||||
|
// BATTERY_CONFIG.vbatmaxcellvoltage = data.readU8() / 10; // 10-50
|
||||||
|
// BATTERY_CONFIG.vbatwarningcellvoltage = data.readU8() / 10; // 10-50
|
||||||
|
// break;
|
||||||
|
case MSPCodes.MSP_MOTOR_3D_CONFIG:
|
||||||
|
MOTOR_3D_CONFIG.deadband3d_low = data.readU16();
|
||||||
|
MOTOR_3D_CONFIG.deadband3d_high = data.readU16();
|
||||||
|
MOTOR_3D_CONFIG.neutral = data.readU16();
|
||||||
if (semver.lt(CONFIG.apiVersion, "1.17.0")) {
|
if (semver.lt(CONFIG.apiVersion, "1.17.0")) {
|
||||||
_3D.deadband3d_throttle = data.readU16();
|
RC_DEADBAND_CONFIG.deadband3d_throttle = data.readU16();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_BOXNAMES:
|
case MSPCodes.MSP_BOXNAMES:
|
||||||
|
@ -341,12 +422,12 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_RC_DEADBAND:
|
case MSPCodes.MSP_RC_DEADBAND:
|
||||||
RC_deadband.deadband = data.readU8();
|
RC_DEADBAND_CONFIG.deadband = data.readU8();
|
||||||
RC_deadband.yaw_deadband = data.readU8();
|
RC_DEADBAND_CONFIG.yaw_deadband = data.readU8();
|
||||||
RC_deadband.alt_hold_deadband = data.readU8();
|
RC_DEADBAND_CONFIG.alt_hold_deadband = data.readU8();
|
||||||
|
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.17.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.17.0")) {
|
||||||
_3D.deadband3d_throttle = data.readU16();
|
RC_DEADBAND_CONFIG.deadband3d_throttle = data.readU16();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_SENSOR_ALIGNMENT:
|
case MSPCodes.MSP_SENSOR_ALIGNMENT:
|
||||||
|
@ -371,8 +452,20 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
||||||
case MSPCodes.MSP_MAG_CALIBRATION:
|
case MSPCodes.MSP_MAG_CALIBRATION:
|
||||||
console.log('Mag calibration executed');
|
console.log('Mag calibration executed');
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_SET_MISC:
|
case MSPCodes.MSP_SET_MOTOR_CONFIG:
|
||||||
console.log('MISC Configuration saved');
|
console.log('Motor Configuration saved');
|
||||||
|
break;
|
||||||
|
case MSPCodes.MSP_SET_GPS_CONFIG:
|
||||||
|
console.log('GPS Configuration saved');
|
||||||
|
break;
|
||||||
|
case MSPCodes.MSP_SET_RSSI_CONFIG:
|
||||||
|
console.log('RSSI Configuration saved');
|
||||||
|
break;
|
||||||
|
// case MSPCodes.MSP_SET_MISC:
|
||||||
|
// console.log('MISC Configuration saved');
|
||||||
|
// break;
|
||||||
|
case MSPCodes.MSP_SET_FEATURE_CONFIG:
|
||||||
|
console.log('Features saved');
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_RESET_CONF:
|
case MSPCodes.MSP_RESET_CONF:
|
||||||
console.log('Settings Reset');
|
console.log('Settings Reset');
|
||||||
|
@ -387,7 +480,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
||||||
console.log('Settings Saved in EEPROM');
|
console.log('Settings Saved in EEPROM');
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_SET_CURRENT_METER_CONFIG:
|
case MSPCodes.MSP_SET_CURRENT_METER_CONFIG:
|
||||||
console.log('Current Settings saved');
|
console.log('Amperage Settings saved');
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_SET_VOLTAGE_METER_CONFIG:
|
case MSPCodes.MSP_SET_VOLTAGE_METER_CONFIG:
|
||||||
console.log('Voltage config saved');
|
console.log('Voltage config saved');
|
||||||
|
@ -433,20 +526,33 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
||||||
case MSPCodes.MSP_SET_RX_MAP:
|
case MSPCodes.MSP_SET_RX_MAP:
|
||||||
console.log('RCMAP saved');
|
console.log('RCMAP saved');
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_BF_CONFIG:
|
case MSPCodes.MSP_MIXER_CONFIG:
|
||||||
BF_CONFIG.mixerConfiguration = data.readU8();
|
MIXER_CONFIG.mixer = data.readU8();
|
||||||
BF_CONFIG.features.setMask(data.readU32());
|
|
||||||
RX_CONFIG.serialrx_provider = data.readU8();
|
|
||||||
BF_CONFIG.board_align_roll = data.read16(); // -180 - 360
|
|
||||||
BF_CONFIG.board_align_pitch = data.read16(); // -180 - 360
|
|
||||||
BF_CONFIG.board_align_yaw = data.read16(); // -180 - 360
|
|
||||||
BF_CONFIG.currentscale = data.read16();
|
|
||||||
BF_CONFIG.currentoffset = data.read16();
|
|
||||||
|
|
||||||
updateTabList(BF_CONFIG.features);
|
|
||||||
|
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_SET_BF_CONFIG:
|
|
||||||
|
case MSPCodes.MSP_FEATURE_CONFIG:
|
||||||
|
FEATURE_CONFIG.features.setMask(data.readU32());
|
||||||
|
|
||||||
|
updateTabList(FEATURE_CONFIG.features);
|
||||||
|
break;
|
||||||
|
|
||||||
|
// case MSPCodes.MSP_BF_CONFIG:
|
||||||
|
// MIXER_CONFIG.mixer = data.readU8();
|
||||||
|
// FEATURE_CONFIG.features.setMask(data.readU32());
|
||||||
|
// RX_CONFIG.serialrx_provider = data.readU8();
|
||||||
|
// BOARD_ALIGNMENT_CONFIG.roll = data.read16(); // -180 - 360
|
||||||
|
// BOARD_ALIGNMENT_CONFIG.pitch = data.read16(); // -180 - 360
|
||||||
|
// BOARD_ALIGNMENT_CONFIG.yaw = data.read16(); // -180 - 360
|
||||||
|
// BF_CONFIG.currentscale = data.read16();
|
||||||
|
// BF_CONFIG.currentoffset = data.read16();
|
||||||
|
//
|
||||||
|
// updateTabList(FEATURE_CONFIG.features);
|
||||||
|
//
|
||||||
|
// break;
|
||||||
|
case MSPCodes.MSP_BOARD_ALIGNMENT_CONFIG:
|
||||||
|
BOARD_ALIGNMENT_CONFIG.roll = data.read16(); // -180 - 360
|
||||||
|
BOARD_ALIGNMENT_CONFIG.pitch = data.read16(); // -180 - 360
|
||||||
|
BOARD_ALIGNMENT_CONFIG.yaw = data.read16(); // -180 - 360
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_SET_REBOOT:
|
case MSPCodes.MSP_SET_REBOOT:
|
||||||
console.log('Reboot request accepted');
|
console.log('Reboot request accepted');
|
||||||
|
@ -582,22 +688,11 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSPCodes.MSP_CHANNEL_FORWARDING:
|
|
||||||
for (var i = 0; i < data.byteLength && i < SERVO_CONFIG.length; i ++) {
|
|
||||||
var channelIndex = data.readU8();
|
|
||||||
if (channelIndex < 255) {
|
|
||||||
SERVO_CONFIG[i].indexOfChannelToForward = channelIndex;
|
|
||||||
} else {
|
|
||||||
SERVO_CONFIG[i].indexOfChannelToForward = undefined;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MSPCodes.MSP_RX_CONFIG:
|
case MSPCodes.MSP_RX_CONFIG:
|
||||||
RX_CONFIG.serialrx_provider = data.readU8();
|
RX_CONFIG.serialrx_provider = data.readU8();
|
||||||
RX_CONFIG.maxcheck = data.readU16();
|
RX_CONFIG.stick_max = data.readU16();
|
||||||
RX_CONFIG.midrc = data.readU16();
|
RX_CONFIG.stick_center = data.readU16();
|
||||||
RX_CONFIG.mincheck = data.readU16();
|
RX_CONFIG.stick_min = data.readU16();
|
||||||
RX_CONFIG.spektrum_sat_bind = data.readU8();
|
RX_CONFIG.spektrum_sat_bind = data.readU8();
|
||||||
RX_CONFIG.rx_min_usec = data.readU16();
|
RX_CONFIG.rx_min_usec = data.readU16();
|
||||||
RX_CONFIG.rx_max_usec = data.readU16();
|
RX_CONFIG.rx_max_usec = data.readU16();
|
||||||
|
@ -907,7 +1002,7 @@ MspHelper.prototype.process_data = function(dataHandler) {
|
||||||
case MSPCodes.MSP_SET_RESET_CURR_PID:
|
case MSPCodes.MSP_SET_RESET_CURR_PID:
|
||||||
console.log('Current PID profile reset');
|
console.log('Current PID profile reset');
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_SET_3D:
|
case MSPCodes.MSP_SET_MOTOR_3D_CONFIG:
|
||||||
console.log('3D settings saved');
|
console.log('3D settings saved');
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_SET_RC_DEADBAND:
|
case MSPCodes.MSP_SET_RC_DEADBAND:
|
||||||
|
@ -985,16 +1080,25 @@ MspHelper.prototype.crunch = function(code) {
|
||||||
var buffer = [];
|
var buffer = [];
|
||||||
var self = this;
|
var self = this;
|
||||||
switch (code) {
|
switch (code) {
|
||||||
case MSPCodes.MSP_SET_BF_CONFIG:
|
case MSPCodes.MSP_SET_FEATURE_CONFIG:
|
||||||
var featureMask = BF_CONFIG.features.getMask();
|
var featureMask = FEATURE_CONFIG.features.getMask();
|
||||||
buffer.push8(BF_CONFIG.mixerConfiguration)
|
buffer.push32(featureMask);
|
||||||
.push32(featureMask)
|
break;
|
||||||
.push8(RX_CONFIG.serialrx_provider)
|
// case MSPCodes.MSP_SET_BF_CONFIG:
|
||||||
.push16(BF_CONFIG.board_align_roll)
|
// var featureMask = FEATURE_CONFIG.features.getMask();
|
||||||
.push16(BF_CONFIG.board_align_pitch)
|
// buffer.push8(MIXER_CONFIG.mixer)
|
||||||
.push16(BF_CONFIG.board_align_yaw)
|
// .push32(featureMask)
|
||||||
.push16(BF_CONFIG.currentscale)
|
// .push8(RX_CONFIG.serialrx_provider)
|
||||||
.push16(BF_CONFIG.currentoffset);
|
// .push16(BOARD_ALIGNMENT_CONFIG.roll)
|
||||||
|
// .push16(BOARD_ALIGNMENT_CONFIG.pitch)
|
||||||
|
// .push16(BOARD_ALIGNMENT_CONFIG.yaw)
|
||||||
|
// .push16(BF_CONFIG.currentscale)
|
||||||
|
// .push16(BF_CONFIG.currentoffset);
|
||||||
|
// break;
|
||||||
|
case MSPCodes.MSP_SET_BOARD_ALIGNMENT_CONFIG:
|
||||||
|
buffer.push16(BOARD_ALIGNMENT_CONFIG.roll)
|
||||||
|
.push16(BOARD_ALIGNMENT_CONFIG.pitch)
|
||||||
|
.push16(BOARD_ALIGNMENT_CONFIG.yaw);
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_SET_PID_CONTROLLER:
|
case MSPCodes.MSP_SET_PID_CONTROLLER:
|
||||||
buffer.push8(PID.controller);
|
buffer.push8(PID.controller);
|
||||||
|
@ -1042,51 +1146,71 @@ MspHelper.prototype.crunch = function(code) {
|
||||||
buffer.push8(ARMING_CONFIG.auto_disarm_delay)
|
buffer.push8(ARMING_CONFIG.auto_disarm_delay)
|
||||||
.push8(ARMING_CONFIG.disarm_kill_switch);
|
.push8(ARMING_CONFIG.disarm_kill_switch);
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_SET_LOOP_TIME:
|
case MSPCodes.MSP_SET_MOTOR_CONFIG:
|
||||||
buffer.push16(FC_CONFIG.loopTime);
|
buffer.push16(MOTOR_CONFIG.minthrottle)
|
||||||
|
.push16(MOTOR_CONFIG.maxthrottle)
|
||||||
|
.push16(MOTOR_CONFIG.mincommand);
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_SET_MISC:
|
case MSPCodes.MSP_SET_GPS_CONFIG:
|
||||||
buffer.push16(RX_CONFIG.midrc)
|
buffer.push8(GPS_CONFIG.provider)
|
||||||
.push16(MISC.minthrottle)
|
.push8(GPS_CONFIG.ublox_sbas);
|
||||||
.push16(MISC.maxthrottle)
|
|
||||||
.push16(MISC.mincommand)
|
|
||||||
.push16(MISC.failsafe_throttle)
|
|
||||||
.push8(MISC.gps_type)
|
|
||||||
.push8(MISC.gps_baudrate)
|
|
||||||
.push8(MISC.gps_ubx_sbas)
|
|
||||||
.push8(MISC.multiwiicurrentoutput)
|
|
||||||
.push8(MISC.rssi_channel)
|
|
||||||
.push8(MISC.placeholder2);
|
|
||||||
if (semver.lt(CONFIG.apiVersion, "1.18.0")) {
|
|
||||||
buffer.push16(Math.round(MISC.mag_declination * 10));
|
|
||||||
} else {
|
|
||||||
buffer.push16(Math.round(MISC.mag_declination * 100));
|
|
||||||
}
|
|
||||||
buffer.push8(MISC.vbatscale)
|
|
||||||
.push8(Math.round(MISC.vbatmincellvoltage * 10))
|
|
||||||
.push8(Math.round(MISC.vbatmaxcellvoltage * 10))
|
|
||||||
.push8(Math.round(MISC.vbatwarningcellvoltage * 10));
|
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_SET_VOLTAGE_METER_CONFIG:
|
case MSPCodes.MSP_SET_COMPASS_CONFIG:
|
||||||
buffer.push8(MISC.vbatscale)
|
buffer.push16(Math.round(COMPASS_CONFIG.mag_declination * 100));
|
||||||
.push8(Math.round(MISC.vbatmincellvoltage * 10))
|
|
||||||
.push8(Math.round(MISC.vbatmaxcellvoltage * 10))
|
|
||||||
.push8(Math.round(MISC.vbatwarningcellvoltage * 10));
|
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.23.0")) {
|
|
||||||
buffer.push8(MISC.batterymetertype);
|
|
||||||
}
|
|
||||||
break;
|
break;
|
||||||
case MSPCodes.MSP_SET_CURRENT_METER_CONFIG:
|
case MSPCodes.MSP_SET_RSSI_CONFIG:
|
||||||
buffer.push16(BF_CONFIG.currentscale)
|
buffer.push8(RSSI_CONFIG.channel);
|
||||||
.push16(BF_CONFIG.currentoffset)
|
|
||||||
.push8(BF_CONFIG.currentmetertype)
|
|
||||||
.push16(BF_CONFIG.batterycapacity)
|
|
||||||
break;
|
break;
|
||||||
|
// case MSPCodes.MSP_SET_MISC:
|
||||||
|
// buffer.push16(RX_CONFIG.stick_center)
|
||||||
|
// .push16(MOTOR_CONFIG.minthrottle)
|
||||||
|
// .push16(MOTOR_CONFIG.maxthrottle)
|
||||||
|
// .push16(MOTOR_CONFIG.mincommand)
|
||||||
|
// .push16(MISC.failsafe_throttle)
|
||||||
|
// .push8(GPS_CONFIG.provider)
|
||||||
|
// .push8(GPS_CONFIG.baudrate)
|
||||||
|
// .push8(GPS_CONFIG.ublox_sbas)
|
||||||
|
// .push8(MISC.multiwiicurrentoutput)
|
||||||
|
// .push8(RSSI_CONFIG.channel)
|
||||||
|
// .push8(MISC.placeholder2);
|
||||||
|
// if (semver.lt(CONFIG.apiVersion, "1.18.0")) {
|
||||||
|
// buffer.push16(Math.round(COMPASS_CONFIG.mag_declination * 10));
|
||||||
|
// } else {
|
||||||
|
// buffer.push16(Math.round(COMPASS_CONFIG.mag_declination * 100));
|
||||||
|
// }
|
||||||
|
// buffer.push8(MISC.vbatscale)
|
||||||
|
// .push8(Math.round(BATTERY_CONFIG.vbatmincellvoltage * 10))
|
||||||
|
// .push8(Math.round(BATTERY_CONFIG.vbatmaxcellvoltage * 10))
|
||||||
|
// .push8(Math.round(BATTERY_CONFIG.vbatwarningcellvoltage * 10));
|
||||||
|
// break;
|
||||||
|
case MSPCodes.MSP_SET_BATTERY_CONFIG:
|
||||||
|
buffer.push8(Math.round(BATTERY_CONFIG.vbatmincellvoltage * 10))
|
||||||
|
.push8(Math.round(BATTERY_CONFIG.vbatmaxcellvoltage * 10))
|
||||||
|
.push8(Math.round(BATTERY_CONFIG.vbatwarningcellvoltage * 10))
|
||||||
|
.push16(BATTERY_CONFIG.batterycapacity)
|
||||||
|
.push8(BATTERY_CONFIG.voltageMeterSource)
|
||||||
|
.push8(BATTERY_CONFIG.currentMeterSource);
|
||||||
|
break;
|
||||||
|
// case MSPCodes.MSP_SET_VOLTAGE_METER_CONFIG:
|
||||||
|
// buffer.push8(MISC.vbatscale)
|
||||||
|
// .push8(Math.round(BATTERY_CONFIG.vbatmincellvoltage * 10))
|
||||||
|
// .push8(Math.round(BATTERY_CONFIG.vbatmaxcellvoltage * 10))
|
||||||
|
// .push8(Math.round(BATTERY_CONFIG.vbatwarningcellvoltage * 10));
|
||||||
|
// if (semver.gte(CONFIG.apiVersion, "1.23.0")) {
|
||||||
|
// buffer.push8(BATTERY_CONFIG.voltageMeterSource);
|
||||||
|
// }
|
||||||
|
// break;
|
||||||
|
// case MSPCodes.MSP_SET_CURRENT_METER_CONFIG:
|
||||||
|
// buffer.push16(BF_CONFIG.currentscale)
|
||||||
|
// .push16(BF_CONFIG.currentoffset)
|
||||||
|
// .push8(BATTERY_CONFIG.currentMeterSource)
|
||||||
|
// .push16(BF_CONFIG.batterycapacity)
|
||||||
|
// break;
|
||||||
case MSPCodes.MSP_SET_RX_CONFIG:
|
case MSPCodes.MSP_SET_RX_CONFIG:
|
||||||
buffer.push8(RX_CONFIG.serialrx_provider)
|
buffer.push8(RX_CONFIG.serialrx_provider)
|
||||||
.push16(RX_CONFIG.maxcheck)
|
.push16(RX_CONFIG.stick_max)
|
||||||
.push16(RX_CONFIG.midrc)
|
.push16(RX_CONFIG.stick_center)
|
||||||
.push16(RX_CONFIG.mincheck)
|
.push16(RX_CONFIG.stick_min)
|
||||||
.push8(RX_CONFIG.spektrum_sat_bind)
|
.push8(RX_CONFIG.spektrum_sat_bind)
|
||||||
.push16(RX_CONFIG.rx_min_usec)
|
.push16(RX_CONFIG.rx_min_usec)
|
||||||
.push16(RX_CONFIG.rx_max_usec);
|
.push16(RX_CONFIG.rx_max_usec);
|
||||||
|
@ -1156,21 +1280,21 @@ MspHelper.prototype.crunch = function(code) {
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSPCodes.MSP_SET_3D:
|
case MSPCodes.MSP_SET_MOTOR_3D_CONFIG:
|
||||||
buffer.push16(_3D.deadband3d_low)
|
buffer.push16(MOTOR_3D_CONFIG.deadband3d_low)
|
||||||
.push16(_3D.deadband3d_high)
|
.push16(MOTOR_3D_CONFIG.deadband3d_high)
|
||||||
.push16(_3D.neutral3d);
|
.push16(MOTOR_3D_CONFIG.neutral);
|
||||||
if (semver.lt(CONFIG.apiVersion, "1.17.0")) {
|
if (semver.lt(CONFIG.apiVersion, "1.17.0")) {
|
||||||
buffer.push16(_3D.deadband3d_throttle);
|
buffer.push16(RC_DEADBAND_CONFIG.deadband3d_throttle);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSPCodes.MSP_SET_RC_DEADBAND:
|
case MSPCodes.MSP_SET_RC_DEADBAND:
|
||||||
buffer.push8(RC_deadband.deadband)
|
buffer.push8(RC_DEADBAND_CONFIG.deadband)
|
||||||
.push8(RC_deadband.yaw_deadband)
|
.push8(RC_DEADBAND_CONFIG.yaw_deadband)
|
||||||
.push8(RC_deadband.alt_hold_deadband);
|
.push8(RC_DEADBAND_CONFIG.alt_hold_deadband);
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.17.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.17.0")) {
|
||||||
buffer.push16(_3D.deadband3d_throttle);
|
buffer.push16(RC_DEADBAND_CONFIG.deadband3d_throttle);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
|
|
@ -267,24 +267,11 @@ function onConnect() {
|
||||||
$('#tabs ul.mode-connected-cli').show();
|
$('#tabs ul.mode-connected-cli').show();
|
||||||
|
|
||||||
if (CONFIG.flightControllerVersion !== '') {
|
if (CONFIG.flightControllerVersion !== '') {
|
||||||
BF_CONFIG.features = new Features(CONFIG);
|
FEATURE_CONFIG.features = new Features(CONFIG);
|
||||||
|
|
||||||
$('#tabs ul.mode-connected').show();
|
$('#tabs ul.mode-connected').show();
|
||||||
|
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
|
||||||
MSP.send_message(MSPCodes.MSP_STATUS_EX, false, false);
|
MSP.send_message(MSPCodes.MSP_STATUS_EX, false, false);
|
||||||
} else {
|
|
||||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false);
|
|
||||||
|
|
||||||
if (CONFIG.flightControllerIdentifier === 'BTFL' && semver.gte(CONFIG.flightControllerVersion, "2.4.0")) {
|
|
||||||
CONFIG.numProfiles = 2;
|
|
||||||
$('.tab-pid_tuning select[name="profile"] .profile3').hide();
|
|
||||||
} else {
|
|
||||||
CONFIG.numProfiles = 3;
|
|
||||||
$('.tab-pid_tuning select[name="rate_profile"]').hide();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
MSP.send_message(MSPCodes.MSP_DATAFLASH_SUMMARY, false, false);
|
MSP.send_message(MSPCodes.MSP_DATAFLASH_SUMMARY, false, false);
|
||||||
|
|
||||||
startLiveDataRefreshTimer();
|
startLiveDataRefreshTimer();
|
||||||
|
@ -492,13 +479,13 @@ function update_live_status() {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (ANALOG != undefined) {
|
if (ANALOG != undefined) {
|
||||||
var nbCells = Math.floor(ANALOG.voltage / MISC.vbatmaxcellvoltage) + 1;
|
var nbCells = Math.floor(ANALOG.voltage / BATTERY_CONFIG.vbatmaxcellvoltage) + 1;
|
||||||
if (ANALOG.voltage == 0)
|
if (ANALOG.voltage == 0)
|
||||||
nbCells = 1;
|
nbCells = 1;
|
||||||
|
|
||||||
var min = MISC.vbatmincellvoltage * nbCells;
|
var min = BATTERY_CONFIG.vbatmincellvoltage * nbCells;
|
||||||
var max = MISC.vbatmaxcellvoltage * nbCells;
|
var max = BATTERY_CONFIG.vbatmaxcellvoltage * nbCells;
|
||||||
var warn = MISC.vbatwarningcellvoltage * nbCells;
|
var warn = BATTERY_CONFIG.vbatwarningcellvoltage * nbCells;
|
||||||
|
|
||||||
$(".battery-status").css({
|
$(".battery-status").css({
|
||||||
width: ((ANALOG.voltage - min) / (max - min) * 100) + "%",
|
width: ((ANALOG.voltage - min) / (max - min) * 100) + "%",
|
||||||
|
|
8
main.js
8
main.js
|
@ -228,8 +228,8 @@ $(document).ready(function () {
|
||||||
chrome.storage.local.set({'permanentExpertMode': checked});
|
chrome.storage.local.set({'permanentExpertMode': checked});
|
||||||
|
|
||||||
$('input[name="expertModeCheckbox"]').prop('checked', checked).change();
|
$('input[name="expertModeCheckbox"]').prop('checked', checked).change();
|
||||||
if (BF_CONFIG) {
|
if (FEATURE_CONFIG) {
|
||||||
updateTabList(BF_CONFIG.features);
|
updateTabList(FEATURE_CONFIG.features);
|
||||||
}
|
}
|
||||||
|
|
||||||
}).change();
|
}).change();
|
||||||
|
@ -362,8 +362,8 @@ $(document).ready(function () {
|
||||||
}
|
}
|
||||||
|
|
||||||
$('input[name="expertModeCheckbox"]').change(function () {
|
$('input[name="expertModeCheckbox"]').change(function () {
|
||||||
if (BF_CONFIG) {
|
if (FEATURE_CONFIG) {
|
||||||
updateTabList(BF_CONFIG.features);
|
updateTabList(FEATURE_CONFIG.features);
|
||||||
}
|
}
|
||||||
}).change();
|
}).change();
|
||||||
});
|
});
|
||||||
|
|
|
@ -292,7 +292,7 @@
|
||||||
width: 150px;
|
width: 150px;
|
||||||
}
|
}
|
||||||
|
|
||||||
.tab-configuration .currentmetertype {
|
.tab-configuration .currentMeterSource {
|
||||||
border: 1px solid silver;
|
border: 1px solid silver;
|
||||||
margin-right: 5px;
|
margin-right: 5px;
|
||||||
float: left;
|
float: left;
|
||||||
|
|
|
@ -121,7 +121,8 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="clear-both"></div>
|
<div class="clear-both"></div>
|
||||||
<div class="leftWrapper board">
|
|
||||||
|
<div class="leftWrapper board acc">
|
||||||
<div class="gui_box grey">
|
<div class="gui_box grey">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title" i18n="configurationBoardAlignment"></div>
|
<div class="spacer_box_title" i18n="configurationBoardAlignment"></div>
|
||||||
|
@ -179,8 +180,6 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
|
||||||
<div class="rightWrapper acc">
|
|
||||||
<div class="gui_box grey">
|
<div class="gui_box grey">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title" i18n="configurationAccelTrims"></div>
|
<div class="spacer_box_title" i18n="configurationAccelTrims"></div>
|
||||||
|
@ -199,34 +198,10 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="clear-both"></div>
|
<div class="rightWrapper 3d">
|
||||||
<div class="leftWrapper">
|
<div class="gui_box grey">
|
||||||
<div class="gui_box grey" style="margin-bottom:20px;">
|
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title" i18n="configurationReceiver"></div>
|
<div class="spacer_box_title" i18n="configuration3d"></div>
|
||||||
</div>
|
|
||||||
<div class="spacer_box" style="padding-bottom:15px;">
|
|
||||||
<select class="features rxMode" name="rxMode">
|
|
||||||
<!-- list generated here -->
|
|
||||||
</select>
|
|
||||||
<span i18n="configurationReceiverMode"></span>
|
|
||||||
</div>
|
|
||||||
<div class="serialRXBox spacer_box" style="padding-bottom:10px;">
|
|
||||||
<div class="note spacerbottom">
|
|
||||||
<div class="note_spacer">
|
|
||||||
<p i18n="configurationSerialRXHelp"></p>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<select class="serialRX">
|
|
||||||
<!-- list generated here -->
|
|
||||||
</select>
|
|
||||||
<span i18n="configurationSerialRX"></span>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<div class="gui_box grey" style="margin-bottom:20px;">
|
|
||||||
<div class="gui_box_titlebar">
|
|
||||||
<div class="spacer_box_title" i18n="configurationRSSI"></div>
|
|
||||||
<div class="helpicon cf_tip" i18n_title="configurationRSSIHelp"></div>
|
|
||||||
</div>
|
</div>
|
||||||
<div class="spacer_box">
|
<div class="spacer_box">
|
||||||
<table cellpadding="0" cellspacing="0">
|
<table cellpadding="0" cellspacing="0">
|
||||||
|
@ -237,12 +212,33 @@
|
||||||
<th i18n="configurationFeatureName"></th>
|
<th i18n="configurationFeatureName"></th>
|
||||||
</tr>
|
</tr>
|
||||||
</thead>
|
</thead>
|
||||||
<tbody class="features rssi">
|
<tbody class="features 3D">
|
||||||
<!-- table generated here -->
|
<!-- table generated here -->
|
||||||
</tbody>
|
</tbody>
|
||||||
</table>
|
</table>
|
||||||
|
<div class="_3dSettings">
|
||||||
|
<div class="number">
|
||||||
|
<label> <input type="number" name="3ddeadbandlow" step="1" min="1250" max="1600" /> <span
|
||||||
|
i18n="configuration3dDeadbandLow"></span>
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
<div class="number">
|
||||||
|
<label> <input type="number" name="3ddeadbandhigh" step="1" min="1400" max="1750" /> <span
|
||||||
|
i18n="configuration3dDeadbandHigh"></span>
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
<div class="number">
|
||||||
|
<label> <input type="number" name="3dneutral" step="1" min="1400" max="1600" /> <span
|
||||||
|
i18n="configuration3dNeutral"></span>
|
||||||
|
</label>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
<div class="clear-both"></div>
|
||||||
|
|
||||||
|
<div class="leftWrapper">
|
||||||
<div class="gui_box grey" style="margin-bottom:20px;">
|
<div class="gui_box grey" style="margin-bottom:20px;">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title" i18n="configurationSystem"></div>
|
<div class="spacer_box_title" i18n="configurationSystem"></div>
|
||||||
|
@ -306,6 +302,32 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
<div class="gui_box grey miscSettings" style="margin-top:10px;">
|
||||||
|
<div class="gui_box_titlebar">
|
||||||
|
<div class="spacer_box_title" i18n="configurationPersonalization"></div>
|
||||||
|
</div>
|
||||||
|
<div class="spacer_box">
|
||||||
|
<div class="number">
|
||||||
|
<label> <input type="text" name="craftName" maxlength="32" style="width:100px;"/> <span
|
||||||
|
i18n="craftName"></span>
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
<div class="gui_box grey miscSettings" style="margin-top:10px;">
|
||||||
|
<div class="gui_box_titlebar">
|
||||||
|
<div class="spacer_box_title" i18n="configurationCamera"></div>
|
||||||
|
</div>
|
||||||
|
<div class="spacer_box">
|
||||||
|
<div class="number fpvCamAngleDegrees">
|
||||||
|
<label> <input type="number" name="fpvCamAngleDegrees" step="1" min="0" max="50" /> <span
|
||||||
|
i18n="configurationFpvCamAngleDegrees"></span>
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
<div class="rightWrapper featuresOther">
|
||||||
<div class="gui_box grey">
|
<div class="gui_box grey">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title" i18n="configurationFeatures"></div>
|
<div class="spacer_box_title" i18n="configurationFeatures"></div>
|
||||||
|
@ -331,10 +353,39 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="rightWrapper current voltage">
|
<div class="clear-both"></div>
|
||||||
<div class="gui_box grey">
|
|
||||||
|
<!-- FIXME move receiver and RSSI to receiver tab -->
|
||||||
|
<div class="leftWrapper receiver">
|
||||||
|
<div class="gui_box grey" style="margin-bottom:20px;">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title" i18n="configurationBatteryVoltage"></div>
|
<div class="spacer_box_title" i18n="configurationReceiver"></div>
|
||||||
|
</div>
|
||||||
|
<div class="spacer_box" style="padding-bottom:15px;">
|
||||||
|
<select class="features rxMode" name="rxMode">
|
||||||
|
<!-- list generated here -->
|
||||||
|
</select>
|
||||||
|
<span i18n="configurationReceiverMode"></span>
|
||||||
|
</div>
|
||||||
|
<div class="serialRXBox spacer_box" style="padding-bottom:10px;">
|
||||||
|
<div class="note spacerbottom">
|
||||||
|
<div class="note_spacer">
|
||||||
|
<p i18n="configurationSerialRXHelp"></p>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
<select class="serialRX">
|
||||||
|
<!-- list generated here -->
|
||||||
|
</select>
|
||||||
|
<span i18n="configurationSerialRX"></span>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
</div>
|
||||||
|
<div class="rightWrapper rssi">
|
||||||
|
<div class="gui_box grey" style="margin-bottom:20px;">
|
||||||
|
<div class="gui_box_titlebar">
|
||||||
|
<div class="spacer_box_title" i18n="configurationRSSI"></div>
|
||||||
|
<div class="helpicon cf_tip" i18n_title="configurationRSSIHelp"></div>
|
||||||
</div>
|
</div>
|
||||||
<div class="spacer_box">
|
<div class="spacer_box">
|
||||||
<table cellpadding="0" cellspacing="0">
|
<table cellpadding="0" cellspacing="0">
|
||||||
|
@ -345,14 +396,32 @@
|
||||||
<th i18n="configurationFeatureName"></th>
|
<th i18n="configurationFeatureName"></th>
|
||||||
</tr>
|
</tr>
|
||||||
</thead>
|
</thead>
|
||||||
<tbody class="features batteryVoltage">
|
<tbody class="features rssi">
|
||||||
<!-- table generated here -->
|
<!-- table generated here -->
|
||||||
</tbody>
|
</tbody>
|
||||||
</table>
|
</table>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
<div class="clear-both"></div>
|
||||||
|
|
||||||
|
<!-- FIXME move current voltage battery to new tab -->
|
||||||
|
<div class="leftWrapper current voltage battery">
|
||||||
|
<div class="gui_box grey">
|
||||||
|
<div class="gui_box_titlebar">
|
||||||
|
<div class="spacer_box_title" i18n="configurationBattery"></div>
|
||||||
|
</div>
|
||||||
|
<div class="spacer_box">
|
||||||
<div class="select batterymetertype vbatmonitoring">
|
<div class="select batterymetertype vbatmonitoring">
|
||||||
<label>
|
<label>
|
||||||
<select class="batterymetertype"><!-- list generated here --></select>
|
<select class="batterymetertype"><!-- list generated here --></select>
|
||||||
<span i18n="configurationBatteryMeterType"></span>
|
<span i18n="configurationBatteryVoltageMeterSource"></span>
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
<div class="select currentMonitoring">
|
||||||
|
<label>
|
||||||
|
<select class="currentMeterSource"><!-- list generated here --></select>
|
||||||
|
<span i18n="configurationBatteryCurrentMeterSource"></span>
|
||||||
</label>
|
</label>
|
||||||
</div>
|
</div>
|
||||||
<div class="number vbatmonitoring">
|
<div class="number vbatmonitoring">
|
||||||
|
@ -370,14 +439,23 @@
|
||||||
i18n="configurationBatteryWarning"></span>
|
i18n="configurationBatteryWarning"></span>
|
||||||
</label>
|
</label>
|
||||||
</div>
|
</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
<div class="gui_box grey">
|
||||||
|
<div class="gui_box_titlebar">
|
||||||
|
<div class="spacer_box_title" i18n="configurationVoltage"></div>
|
||||||
|
</div>
|
||||||
|
<div class="spacer_box">
|
||||||
|
<!-- FIXME move
|
||||||
<div class="number vbatmonitoring vbatCalibration">
|
<div class="number vbatmonitoring vbatCalibration">
|
||||||
<label> <input type="number" name="voltagescale" step="1" min="10" max="255" /> <span
|
<label> <input type="number" name="voltagescale" step="1" min="10" max="255" /> <span
|
||||||
i18n="configurationBatteryScale"></span>
|
i18n="configurationBatteryScale"></span>
|
||||||
</label>
|
</label>
|
||||||
</div>
|
</div>
|
||||||
|
-->
|
||||||
<div class="number vbatmonitoring">
|
<div class="number vbatmonitoring">
|
||||||
<label> <input type="text" name="batteryvoltage" readonly class="disabled" /> <span
|
<label> <input type="text" name="batteryvoltage" readonly class="disabled" /> <span
|
||||||
i18n="configurationBatteryVoltage"></span>
|
i18n="configurationVoltage"></span>
|
||||||
</label>
|
</label>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
@ -387,24 +465,6 @@
|
||||||
<div class="spacer_box_title" i18n="configurationCurrent"></div>
|
<div class="spacer_box_title" i18n="configurationCurrent"></div>
|
||||||
</div>
|
</div>
|
||||||
<div class="spacer_box">
|
<div class="spacer_box">
|
||||||
<table cellpadding="0" cellspacing="0">
|
|
||||||
<thead>
|
|
||||||
<tr>
|
|
||||||
<th i18n="configurationFeatureEnabled"></th>
|
|
||||||
<th i18n="configurationFeatureDescription"></th>
|
|
||||||
<th i18n="configurationFeatureName"></th>
|
|
||||||
</tr>
|
|
||||||
</thead>
|
|
||||||
<tbody class="features batteryCurrent">
|
|
||||||
<!-- table generated here -->
|
|
||||||
</tbody>
|
|
||||||
</table>
|
|
||||||
<div class="select currentMonitoring">
|
|
||||||
<label>
|
|
||||||
<select class="currentmetertype"><!-- list generated here --></select>
|
|
||||||
<span i18n="configurationCurrentMeterType"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
<div class="number currentMonitoring currentCalibration">
|
<div class="number currentMonitoring currentCalibration">
|
||||||
<label> <input type="number" name="currentscale" step="1" min="-16000" max="16000" /> <span
|
<label> <input type="number" name="currentscale" step="1" min="-16000" max="16000" /> <span
|
||||||
i18n="configurationCurrentScale"></span>
|
i18n="configurationCurrentScale"></span>
|
||||||
|
@ -416,21 +476,15 @@
|
||||||
</label>
|
</label>
|
||||||
</div>
|
</div>
|
||||||
<div class="number currentMonitoring currentOutput">
|
<div class="number currentMonitoring currentOutput">
|
||||||
<label>
|
<label> <input type="text" name="batterycurrent" readonly class="disabled" /> <span
|
||||||
<input type="text" name="batterycurrent" readonly class="disabled" /> <span
|
|
||||||
i18n="configurationBatteryCurrent"></span>
|
i18n="configurationBatteryCurrent"></span>
|
||||||
</label>
|
</label>
|
||||||
</div>
|
</div>
|
||||||
<div class="checkbox currentMonitoring currentOutput">
|
|
||||||
<div class="numberspacer">
|
|
||||||
<input type="checkbox" name="multiwiicurrentoutput" class="toggle" />
|
|
||||||
</div>
|
|
||||||
<label> <span i18n="configurationBatteryMultiwiiCurrent"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="gui_box grey gps" style="margin-top:10px;">
|
<div class="rightWrapper gps">
|
||||||
|
<div class="gui_box grey gps">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title" i18n="configurationGPS"></div>
|
<div class="spacer_box_title" i18n="configurationGPS"></div>
|
||||||
</div>
|
</div>
|
||||||
|
@ -481,66 +535,7 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="gui_box grey" style="margin-top:10px;">
|
|
||||||
<div class="gui_box_titlebar">
|
|
||||||
<div class="spacer_box_title" i18n="configuration3d"></div>
|
|
||||||
</div>
|
</div>
|
||||||
<div class="spacer_box">
|
|
||||||
<table cellpadding="0" cellspacing="0">
|
|
||||||
<thead>
|
|
||||||
<tr>
|
|
||||||
<th i18n="configurationFeatureEnabled"></th>
|
|
||||||
<th i18n="configurationFeatureDescription"></th>
|
|
||||||
<th i18n="configurationFeatureName"></th>
|
|
||||||
</tr>
|
|
||||||
</thead>
|
|
||||||
<tbody class="features 3D">
|
|
||||||
<!-- table generated here -->
|
|
||||||
</tbody>
|
|
||||||
</table>
|
|
||||||
<div class="_3dSettings">
|
|
||||||
<div class="number">
|
|
||||||
<label> <input type="number" name="3ddeadbandlow" step="1" min="1425" max="1500" /> <span
|
|
||||||
i18n="configuration3dDeadbandLow"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
|
||||||
<label> <input type="number" name="3ddeadbandhigh" step="1" min="1500" max="1575" /> <span
|
|
||||||
i18n="configuration3dDeadbandHigh"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
<div class="number">
|
|
||||||
<label> <input type="number" name="3dneutral" step="1" min="1475" max="1525" /> <span
|
|
||||||
i18n="configuration3dNeutral"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
<div class="number" >
|
|
||||||
<label> <input type="number" name="3ddeadbandthrottle" step="1" min="0" max="1000" /> <span
|
|
||||||
i18n="configuration3dDeadbandThrottle"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<div class="gui_box grey miscSettings" style="margin-top:10px;">
|
|
||||||
<div class="gui_box_titlebar">
|
|
||||||
<div class="spacer_box_title" i18n="configurationMisc"></div>
|
|
||||||
</div>
|
|
||||||
<div class="spacer_box">
|
|
||||||
<div class="number">
|
|
||||||
<label> <input type="text" name="vesselName" maxlength="32" style="width:100px;"/> <span
|
|
||||||
i18n="configurationVesselName"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
<div class="number fpvCamAngleDegrees">
|
|
||||||
<label> <input type="number" name="fpvCamAngleDegrees" step="1" min="0" max="50" /> <span
|
|
||||||
i18n="configurationFpvCamAngleDegrees"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<div class="clear-both"></div>
|
|
||||||
<div class="clear-both"></div>
|
<div class="clear-both"></div>
|
||||||
</div>
|
</div>
|
||||||
<div class="content_toolbar">
|
<div class="content_toolbar">
|
||||||
|
|
|
@ -12,24 +12,39 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_config() {
|
function load_config() {
|
||||||
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, load_serial_config);
|
MSP.send_message(MSPCodes.MSP_FEATURE_CONFIG, false, false, load_serial_config);
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_serial_config() {
|
function load_serial_config() {
|
||||||
var next_callback = load_rc_map;
|
MSP.send_message(MSPCodes.MSP_CF_SERIAL_CONFIG, false, false, load_board_alignment_config);
|
||||||
if (semver.lt(CONFIG.apiVersion, "1.6.0")) {
|
|
||||||
MSP.send_message(MSPCodes.MSP_CF_SERIAL_CONFIG, false, false, next_callback);
|
|
||||||
} else {
|
|
||||||
next_callback();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
function load_board_alignment_config() {
|
||||||
|
MSP.send_message(MSPCodes.MSP_BOARD_ALIGNMENT_CONFIG, false, false, load_rc_map);
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_rc_map() {
|
function load_rc_map() {
|
||||||
MSP.send_message(MSPCodes.MSP_RX_MAP, false, false, load_misc);
|
MSP.send_message(MSPCodes.MSP_RX_MAP, false, false, load_mixer_config);
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_misc() {
|
function load_mixer_config() {
|
||||||
MSP.send_message(MSPCodes.MSP_MISC, false, false, load_acc_trim);
|
MSP.send_message(MSPCodes.MSP_MIXER_CONFIG, false, false, load_rssi_config);
|
||||||
|
}
|
||||||
|
|
||||||
|
function load_rssi_config() {
|
||||||
|
MSP.send_message(MSPCodes.MSP_RSSI_CONFIG, false, false, load_motor_config);
|
||||||
|
}
|
||||||
|
|
||||||
|
function load_motor_config() {
|
||||||
|
MSP.send_message(MSPCodes.MSP_MOTOR_CONFIG, false, false, load_compass_config);
|
||||||
|
}
|
||||||
|
|
||||||
|
function load_compass_config() {
|
||||||
|
MSP.send_message(MSPCodes.MSP_COMPASS_CONFIG, false, false, load_gps_config);
|
||||||
|
}
|
||||||
|
|
||||||
|
function load_gps_config() {
|
||||||
|
MSP.send_message(MSPCodes.MSP_GPS_CONFIG, false, false, load_acc_trim);
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_acc_trim() {
|
function load_acc_trim() {
|
||||||
|
@ -37,18 +52,9 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_arming_config() {
|
function load_arming_config() {
|
||||||
var next_callback = load_loop_time;
|
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
|
||||||
MSP.send_message(MSPCodes.MSP_ARMING_CONFIG, false, false, next_callback);
|
|
||||||
} else {
|
|
||||||
next_callback();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
function load_loop_time() {
|
|
||||||
var next_callback = load_3d;
|
var next_callback = load_3d;
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
||||||
MSP.send_message(MSPCodes.MSP_LOOP_TIME, false, false, next_callback);
|
MSP.send_message(MSPCodes.MSP_ARMING_CONFIG, false, false, next_callback);
|
||||||
} else {
|
} else {
|
||||||
next_callback();
|
next_callback();
|
||||||
}
|
}
|
||||||
|
@ -57,7 +63,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
function load_3d() {
|
function load_3d() {
|
||||||
var next_callback = load_rc_deadband;
|
var next_callback = load_rc_deadband;
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
||||||
MSP.send_message(MSPCodes.MSP_3D, false, false, next_callback);
|
MSP.send_message(MSPCodes.MSP_MOTOR_3D_CONFIG, false, false, next_callback);
|
||||||
} else {
|
} else {
|
||||||
next_callback();
|
next_callback();
|
||||||
}
|
}
|
||||||
|
@ -109,8 +115,17 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_battery() {
|
function load_battery() {
|
||||||
|
var next_callback = load_voltage;
|
||||||
|
if (semver.gte(CONFIG.apiVersion, "1.33.0")) {
|
||||||
|
MSP.send_message(MSPCodes.MSP_BATTERY_CONFIG, false, false, next_callback);
|
||||||
|
} else {
|
||||||
|
next_callback();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
function load_voltage() {
|
||||||
var next_callback = load_current;
|
var next_callback = load_current;
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.33.0")) {
|
||||||
MSP.send_message(MSPCodes.MSP_VOLTAGE_METER_CONFIG, false, false, next_callback);
|
MSP.send_message(MSPCodes.MSP_VOLTAGE_METER_CONFIG, false, false, next_callback);
|
||||||
} else {
|
} else {
|
||||||
next_callback();
|
next_callback();
|
||||||
|
@ -119,7 +134,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
|
|
||||||
function load_current() {
|
function load_current() {
|
||||||
var next_callback = load_rx_config;
|
var next_callback = load_rx_config;
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.33.0")) {
|
||||||
MSP.send_message(MSPCodes.MSP_CURRENT_METER_CONFIG, false, false, next_callback);
|
MSP.send_message(MSPCodes.MSP_CURRENT_METER_CONFIG, false, false, next_callback);
|
||||||
} else {
|
} else {
|
||||||
next_callback();
|
next_callback();
|
||||||
|
@ -162,17 +177,17 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
mixer_list_e.change(function () {
|
mixer_list_e.change(function () {
|
||||||
var val = parseInt($(this).val());
|
var val = parseInt($(this).val());
|
||||||
|
|
||||||
BF_CONFIG.mixerConfiguration = val;
|
MIXER_CONFIG.mixer = val;
|
||||||
|
|
||||||
$('.mixerPreview img').attr('src', './resources/motor_order/' + mixerList[val - 1].image + '.svg');
|
$('.mixerPreview img').attr('src', './resources/motor_order/' + mixerList[val - 1].image + '.svg');
|
||||||
});
|
});
|
||||||
|
|
||||||
// select current mixer configuration
|
// select current mixer configuration
|
||||||
mixer_list_e.val(BF_CONFIG.mixerConfiguration).change();
|
mixer_list_e.val(MIXER_CONFIG.mixer).change();
|
||||||
|
|
||||||
var features_e = $('.tab-configuration .features');
|
var features_e = $('.tab-configuration .features');
|
||||||
|
|
||||||
BF_CONFIG.features.generateElements(features_e);
|
FEATURE_CONFIG.features.generateElements(features_e);
|
||||||
|
|
||||||
// translate to user-selected language
|
// translate to user-selected language
|
||||||
localize();
|
localize();
|
||||||
|
@ -357,7 +372,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
$('.hardwareSelection').hide();
|
$('.hardwareSelection').hide();
|
||||||
}
|
}
|
||||||
|
|
||||||
$('input[name="vesselName"]').val(CONFIG.name);
|
$('input[name="craftName"]').val(CONFIG.name);
|
||||||
|
|
||||||
|
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
||||||
|
@ -399,10 +414,10 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
|
|
||||||
gps_protocol_e.change(function () {
|
gps_protocol_e.change(function () {
|
||||||
MISC.gps_type = parseInt($(this).val());
|
GPS_CONFIG.provider = parseInt($(this).val());
|
||||||
});
|
});
|
||||||
|
|
||||||
gps_protocol_e.val(MISC.gps_type);
|
gps_protocol_e.val(GPS_CONFIG.provider);
|
||||||
|
|
||||||
|
|
||||||
var gps_baudrate_e = $('select.gps_baudrate');
|
var gps_baudrate_e = $('select.gps_baudrate');
|
||||||
|
@ -427,10 +442,10 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
|
|
||||||
gps_ubx_sbas_e.change(function () {
|
gps_ubx_sbas_e.change(function () {
|
||||||
MISC.gps_ubx_sbas = parseInt($(this).val());
|
GPS_CONFIG.ublox_sbas = parseInt($(this).val());
|
||||||
});
|
});
|
||||||
|
|
||||||
gps_ubx_sbas_e.val(MISC.gps_ubx_sbas);
|
gps_ubx_sbas_e.val(GPS_CONFIG.ublox_sbas);
|
||||||
|
|
||||||
|
|
||||||
// generate serial RX
|
// generate serial RX
|
||||||
|
@ -483,16 +498,16 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
$('#content').scrollTop((scrollPosition) ? scrollPosition : 0);
|
$('#content').scrollTop((scrollPosition) ? scrollPosition : 0);
|
||||||
|
|
||||||
// fill board alignment
|
// fill board alignment
|
||||||
$('input[name="board_align_roll"]').val(BF_CONFIG.board_align_roll);
|
$('input[name="board_align_roll"]').val(BOARD_ALIGNMENT_CONFIG.roll);
|
||||||
$('input[name="board_align_pitch"]').val(BF_CONFIG.board_align_pitch);
|
$('input[name="board_align_pitch"]').val(BOARD_ALIGNMENT_CONFIG.pitch);
|
||||||
$('input[name="board_align_yaw"]').val(BF_CONFIG.board_align_yaw);
|
$('input[name="board_align_yaw"]').val(BOARD_ALIGNMENT_CONFIG.yaw);
|
||||||
|
|
||||||
// fill accel trims
|
// fill accel trims
|
||||||
$('input[name="roll"]').val(CONFIG.accelerometerTrims[1]);
|
$('input[name="roll"]').val(CONFIG.accelerometerTrims[1]);
|
||||||
$('input[name="pitch"]').val(CONFIG.accelerometerTrims[0]);
|
$('input[name="pitch"]').val(CONFIG.accelerometerTrims[0]);
|
||||||
|
|
||||||
// fill magnetometer
|
// fill magnetometer
|
||||||
$('input[name="mag_declination"]').val(MISC.mag_declination.toFixed(2));
|
$('input[name="mag_declination"]').val(COMPASS_CONFIG.mag_declination.toFixed(2));
|
||||||
|
|
||||||
//fill motor disarm params and FC loop time
|
//fill motor disarm params and FC loop time
|
||||||
if(semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
if(semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
||||||
|
@ -504,13 +519,16 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// fill throttle
|
// fill throttle
|
||||||
$('input[name="minthrottle"]').val(MISC.minthrottle);
|
$('input[name="minthrottle"]').val(MOTOR_CONFIG.minthrottle);
|
||||||
$('input[name="maxthrottle"]').val(MISC.maxthrottle);
|
$('input[name="maxthrottle"]').val(MOTOR_CONFIG.maxthrottle);
|
||||||
$('input[name="mincommand"]').val(MISC.mincommand);
|
$('input[name="mincommand"]').val(MOTOR_CONFIG.mincommand);
|
||||||
|
|
||||||
// fill battery
|
// fill battery
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
if (semver.lt(CONFIG.apiVersion, "1.33.0")) {
|
||||||
|
$('div.battery').hide();
|
||||||
|
} else {
|
||||||
var batteryMeterTypes = [
|
var batteryMeterTypes = [
|
||||||
|
'None',
|
||||||
'Onboard ADC',
|
'Onboard ADC',
|
||||||
'ESC Sensor'
|
'ESC Sensor'
|
||||||
];
|
];
|
||||||
|
@ -521,58 +539,63 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
|
|
||||||
batteryMeterType_e.change(function () {
|
batteryMeterType_e.change(function () {
|
||||||
MISC.batterymetertype = parseInt($(this).val());
|
BATTERY_CONFIG.voltageMeterSource = parseInt($(this).val());
|
||||||
checkUpdateVbatControls();
|
checkUpdateVbatControls();
|
||||||
});
|
});
|
||||||
batteryMeterType_e.val(MISC.batterymetertype).change();
|
batteryMeterType_e.val(BATTERY_CONFIG.voltageMeterSource).change();
|
||||||
} else {
|
|
||||||
$('div.batterymetertype').hide();
|
|
||||||
}
|
|
||||||
|
|
||||||
$('input[name="mincellvoltage"]').val(MISC.vbatmincellvoltage);
|
$('input[name="mincellvoltage"]').val(BATTERY_CONFIG.vbatmincellvoltage);
|
||||||
$('input[name="maxcellvoltage"]').val(MISC.vbatmaxcellvoltage);
|
$('input[name="maxcellvoltage"]').val(BATTERY_CONFIG.vbatmaxcellvoltage);
|
||||||
$('input[name="warningcellvoltage"]').val(MISC.vbatwarningcellvoltage);
|
$('input[name="warningcellvoltage"]').val(BATTERY_CONFIG.vbatwarningcellvoltage);
|
||||||
$('input[name="voltagescale"]').val(MISC.vbatscale);
|
|
||||||
|
|
||||||
|
// FIXME move
|
||||||
|
//$('input[name="voltagescale"]').val(MISC.vbatscale);
|
||||||
|
|
||||||
// fill current
|
// fill current
|
||||||
var currentMeterTypes = [
|
var currentMeterTypes = [
|
||||||
'None',
|
'None',
|
||||||
'Onboard ADC',
|
'Onboard ADC',
|
||||||
'Virtual'
|
'Virtual',
|
||||||
|
'ESC Sensor'
|
||||||
];
|
];
|
||||||
|
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
var currentMeterType_e = $('select.currentMeterSource');
|
||||||
currentMeterTypes.push('ESC Sensor');
|
|
||||||
}
|
|
||||||
|
|
||||||
var currentMeterType_e = $('select.currentmetertype');
|
|
||||||
for (i = 0; i < currentMeterTypes.length; i++) {
|
for (i = 0; i < currentMeterTypes.length; i++) {
|
||||||
currentMeterType_e.append('<option value="' + i + '">' + currentMeterTypes[i] + '</option>');
|
currentMeterType_e.append('<option value="' + i + '">' + currentMeterTypes[i] + '</option>');
|
||||||
}
|
}
|
||||||
|
|
||||||
currentMeterType_e.change(function () {
|
currentMeterType_e.change(function () {
|
||||||
BF_CONFIG.currentmetertype = parseInt($(this).val());
|
BATTERY_CONFIG.currentMeterSource = parseInt($(this).val());
|
||||||
checkUpdateCurrentControls();
|
checkUpdateCurrentControls();
|
||||||
});
|
});
|
||||||
currentMeterType_e.val(BF_CONFIG.currentmetertype).change();
|
currentMeterType_e.val(BATTERY_CONFIG.currentMeterSource).change();
|
||||||
|
|
||||||
$('input[name="currentscale"]').val(BF_CONFIG.currentscale);
|
// FIXME this is a hack - just for display purposes until the battery code is moved to a new tab.
|
||||||
$('input[name="currentoffset"]').val(BF_CONFIG.currentoffset);
|
var meter = CURRENT_METER_CONFIGS[0];
|
||||||
$('input[name="multiwiicurrentoutput"]').prop('checked', MISC.multiwiicurrentoutput !== 0);
|
|
||||||
|
var currentScale_e = $('input[name="currentscale"]');
|
||||||
|
currentScale_e.val(meter.scale);
|
||||||
|
currentScale_e.prop("disabled", true);
|
||||||
|
|
||||||
|
var currentOffset_e = $('input[name="currentoffset"]');
|
||||||
|
currentOffset_e.val(meter.offset);
|
||||||
|
currentOffset_e.prop("disabled", true);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
//fill 3D
|
//fill 3D
|
||||||
if (semver.lt(CONFIG.apiVersion, "1.14.0")) {
|
if (semver.lt(CONFIG.apiVersion, "1.14.0")) {
|
||||||
$('.tab-configuration ._3d').hide();
|
$('.tab-configuration ._3d').hide();
|
||||||
} else {
|
} else {
|
||||||
$('input[name="3ddeadbandlow"]').val(_3D.deadband3d_low);
|
$('input[name="3ddeadbandlow"]').val(MOTOR_3D_CONFIG.deadband3d_low);
|
||||||
$('input[name="3ddeadbandhigh"]').val(_3D.deadband3d_high);
|
$('input[name="3ddeadbandhigh"]').val(MOTOR_3D_CONFIG.deadband3d_high);
|
||||||
$('input[name="3dneutral"]').val(_3D.neutral3d);
|
$('input[name="3dneutral"]').val(MOTOR_3D_CONFIG.neutral);
|
||||||
$('input[name="3ddeadbandthrottle"]').val(_3D.deadband3d_throttle);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// UI hooks
|
// UI hooks
|
||||||
function checkShowDisarmDelay() {
|
function checkShowDisarmDelay() {
|
||||||
if (BF_CONFIG.features.isEnabled('MOTOR_STOP')) {
|
if (FEATURE_CONFIG.features.isEnabled('MOTOR_STOP')) {
|
||||||
$('div.disarmdelay').show();
|
$('div.disarmdelay').show();
|
||||||
} else {
|
} else {
|
||||||
$('div.disarmdelay').hide();
|
$('div.disarmdelay').hide();
|
||||||
|
@ -580,7 +603,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function checkShowSerialRxBox() {
|
function checkShowSerialRxBox() {
|
||||||
if (BF_CONFIG.features.isEnabled('RX_SERIAL')) {
|
if (FEATURE_CONFIG.features.isEnabled('RX_SERIAL')) {
|
||||||
$('div.serialRXBox').show();
|
$('div.serialRXBox').show();
|
||||||
} else {
|
} else {
|
||||||
$('div.serialRXBox').hide();
|
$('div.serialRXBox').hide();
|
||||||
|
@ -588,39 +611,41 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function checkUpdateVbatControls() {
|
function checkUpdateVbatControls() {
|
||||||
if (BF_CONFIG.features.isEnabled('VBAT')) {
|
// FIXME move
|
||||||
$('.vbatmonitoring').show();
|
if (semver.gte(CONFIG.apiVersion, "1.33.0")) {
|
||||||
|
$('.battery').show();
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
|
||||||
$('select.batterymetertype').show();
|
$('select.batterymetertype').show();
|
||||||
|
|
||||||
if (MISC.batterymetertype !== 0) {
|
if (BATTERY_CONFIG.voltageMeterSource !== 0) {
|
||||||
$('.vbatCalibration').hide();
|
$('.vbatCalibration').hide();
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
$('select.batterymetertype').hide();
|
$('.battery').hide();
|
||||||
}
|
|
||||||
} else {
|
|
||||||
$('.vbatmonitoring').hide();
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
function checkUpdateCurrentControls() {
|
function checkUpdateCurrentControls() {
|
||||||
if (BF_CONFIG.features.isEnabled('CURRENT_METER')) {
|
// FIXME move
|
||||||
|
if (semver.gte(CONFIG.apiVersion, "1.33.0")) {
|
||||||
$('.currentMonitoring').show();
|
$('.currentMonitoring').show();
|
||||||
|
|
||||||
switch(BF_CONFIG.currentmetertype) {
|
switch(BATTERY_CONFIG.currentMeterSource) {
|
||||||
case 0:
|
case 1: // ADC
|
||||||
$('.currentCalibration').hide();
|
$('.currentCalibration').show();
|
||||||
$('.currentOutput').hide();
|
$('.currentOutput').show();
|
||||||
|
|
||||||
break;
|
break;
|
||||||
case 3:
|
|
||||||
$('.currentCalibration').hide();
|
|
||||||
}
|
|
||||||
|
|
||||||
if (BF_CONFIG.currentmetertype !== 1 && BF_CONFIG.currentmetertype !== 2) {
|
case 0: // None
|
||||||
|
case 2: // Virtual / FIXME not supported yet
|
||||||
$('.currentCalibration').hide();
|
$('.currentCalibration').hide();
|
||||||
|
$('.currentOutput').hide();
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 3: // ESC
|
||||||
|
$('.currentCalibration').hide();
|
||||||
|
$('.currentOutput').show();
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
$('.currentMonitoring').hide();
|
$('.currentMonitoring').hide();
|
||||||
|
@ -628,7 +653,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function checkUpdateGpsControls() {
|
function checkUpdateGpsControls() {
|
||||||
if (BF_CONFIG.features.isEnabled('GPS')) {
|
if (FEATURE_CONFIG.features.isEnabled('GPS')) {
|
||||||
$('.gpsSettings').show();
|
$('.gpsSettings').show();
|
||||||
} else {
|
} else {
|
||||||
$('.gpsSettings').hide();
|
$('.gpsSettings').hide();
|
||||||
|
@ -636,7 +661,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function checkUpdate3dControls() {
|
function checkUpdate3dControls() {
|
||||||
if (BF_CONFIG.features.isEnabled('3D')) {
|
if (FEATURE_CONFIG.features.isEnabled('3D')) {
|
||||||
$('._3dSettings').show();
|
$('._3dSettings').show();
|
||||||
} else {
|
} else {
|
||||||
$('._3dSettings').hide();
|
$('._3dSettings').hide();
|
||||||
|
@ -646,8 +671,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
$('input.feature', features_e).change(function () {
|
$('input.feature', features_e).change(function () {
|
||||||
var element = $(this);
|
var element = $(this);
|
||||||
|
|
||||||
BF_CONFIG.features.updateData(element);
|
FEATURE_CONFIG.features.updateData(element);
|
||||||
updateTabList(BF_CONFIG.features);
|
updateTabList(FEATURE_CONFIG.features);
|
||||||
|
|
||||||
switch (element.attr('name')) {
|
switch (element.attr('name')) {
|
||||||
case 'MOTOR_STOP':
|
case 'MOTOR_STOP':
|
||||||
|
@ -678,8 +703,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
$(features_e).filter('select').change(function () {
|
$(features_e).filter('select').change(function () {
|
||||||
var element = $(this);
|
var element = $(this);
|
||||||
|
|
||||||
BF_CONFIG.features.updateData(element);
|
FEATURE_CONFIG.features.updateData(element);
|
||||||
updateTabList(BF_CONFIG.features);
|
updateTabList(FEATURE_CONFIG.features);
|
||||||
|
|
||||||
switch (element.attr('name')) {
|
switch (element.attr('name')) {
|
||||||
case 'rxMode':
|
case 'rxMode':
|
||||||
|
@ -708,13 +733,13 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
|
|
||||||
$('a.save').click(function () {
|
$('a.save').click(function () {
|
||||||
// gather data that doesn't have automatic change event bound
|
// gather data that doesn't have automatic change event bound
|
||||||
BF_CONFIG.board_align_roll = parseInt($('input[name="board_align_roll"]').val());
|
BOARD_ALIGNMENT_CONFIG.roll = parseInt($('input[name="board_align_roll"]').val());
|
||||||
BF_CONFIG.board_align_pitch = parseInt($('input[name="board_align_pitch"]').val());
|
BOARD_ALIGNMENT_CONFIG.pitch = parseInt($('input[name="board_align_pitch"]').val());
|
||||||
BF_CONFIG.board_align_yaw = parseInt($('input[name="board_align_yaw"]').val());
|
BOARD_ALIGNMENT_CONFIG.yaw = parseInt($('input[name="board_align_yaw"]').val());
|
||||||
|
|
||||||
CONFIG.accelerometerTrims[1] = parseInt($('input[name="roll"]').val());
|
CONFIG.accelerometerTrims[1] = parseInt($('input[name="roll"]').val());
|
||||||
CONFIG.accelerometerTrims[0] = parseInt($('input[name="pitch"]').val());
|
CONFIG.accelerometerTrims[0] = parseInt($('input[name="pitch"]').val());
|
||||||
MISC.mag_declination = parseFloat($('input[name="mag_declination"]').val());
|
COMPASS_CONFIG.mag_declination = parseFloat($('input[name="mag_declination"]').val());
|
||||||
|
|
||||||
// motor disarm
|
// motor disarm
|
||||||
if(semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
if(semver.gte(CONFIG.apiVersion, "1.8.0")) {
|
||||||
|
@ -722,24 +747,28 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
ARMING_CONFIG.disarm_kill_switch = $('input[id="disarmkillswitch"]').is(':checked') ? 1 : 0;
|
ARMING_CONFIG.disarm_kill_switch = $('input[id="disarmkillswitch"]').is(':checked') ? 1 : 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
MISC.minthrottle = parseInt($('input[name="minthrottle"]').val());
|
MOTOR_CONFIG.minthrottle = parseInt($('input[name="minthrottle"]').val());
|
||||||
MISC.maxthrottle = parseInt($('input[name="maxthrottle"]').val());
|
MOTOR_CONFIG.maxthrottle = parseInt($('input[name="maxthrottle"]').val());
|
||||||
MISC.mincommand = parseInt($('input[name="mincommand"]').val());
|
MOTOR_CONFIG.mincommand = parseInt($('input[name="mincommand"]').val());
|
||||||
|
|
||||||
MISC.vbatmincellvoltage = parseFloat($('input[name="mincellvoltage"]').val());
|
if(semver.gte(CONFIG.apiVersion, "1.33.0")) {
|
||||||
MISC.vbatmaxcellvoltage = parseFloat($('input[name="maxcellvoltage"]').val());
|
BATTERY_CONFIG.vbatmincellvoltage = parseFloat($('input[name="mincellvoltage"]').val());
|
||||||
MISC.vbatwarningcellvoltage = parseFloat($('input[name="warningcellvoltage"]').val());
|
BATTERY_CONFIG.vbatmaxcellvoltage = parseFloat($('input[name="maxcellvoltage"]').val());
|
||||||
MISC.vbatscale = parseInt($('input[name="voltagescale"]').val());
|
BATTERY_CONFIG.vbatwarningcellvoltage = parseFloat($('input[name="warningcellvoltage"]').val());
|
||||||
|
|
||||||
BF_CONFIG.currentscale = parseInt($('input[name="currentscale"]').val());
|
// FIXME move
|
||||||
BF_CONFIG.currentoffset = parseInt($('input[name="currentoffset"]').val());
|
//MISC.vbatscale = parseInt($('input[name="voltagescale"]').val());
|
||||||
MISC.multiwiicurrentoutput = $('input[name="multiwiicurrentoutput"]').is(':checked') ? 1 : 0;
|
|
||||||
|
// FIXME this is a hack
|
||||||
|
var meter = CURRENT_METER_CONFIGS[0];
|
||||||
|
meter.currentscale = parseInt($('input[name="currentscale"]').val());
|
||||||
|
meter.currentoffset = parseInt($('input[name="currentoffset"]').val());
|
||||||
|
}
|
||||||
|
|
||||||
if(semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
if(semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
||||||
_3D.deadband3d_low = parseInt($('input[name="3ddeadbandlow"]').val());
|
MOTOR_3D_CONFIG.deadband3d_low = parseInt($('input[name="3ddeadbandlow"]').val());
|
||||||
_3D.deadband3d_high = parseInt($('input[name="3ddeadbandhigh"]').val());
|
MOTOR_3D_CONFIG.deadband3d_high = parseInt($('input[name="3ddeadbandhigh"]').val());
|
||||||
_3D.neutral3d = parseInt($('input[name="3dneutral"]').val());
|
MOTOR_3D_CONFIG.neutral = parseInt($('input[name="3dneutral"]').val());
|
||||||
_3D.deadband3d_throttle = ($('input[name="3ddeadbandthrottle"]').val());
|
|
||||||
}
|
}
|
||||||
|
|
||||||
SENSOR_ALIGNMENT.align_gyro = parseInt(orientation_gyro_e.val());
|
SENSOR_ALIGNMENT.align_gyro = parseInt(orientation_gyro_e.val());
|
||||||
|
@ -761,121 +790,108 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function save_serial_config() {
|
function save_serial_config() {
|
||||||
if (semver.lt(CONFIG.apiVersion, "1.6.0")) {
|
var next_callback = save_feature_config;
|
||||||
MSP.send_message(MSPCodes.MSP_SET_CF_SERIAL_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_CF_SERIAL_CONFIG), false, save_misc);
|
MSP.send_message(MSPCodes.MSP_SET_CF_SERIAL_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_CF_SERIAL_CONFIG), false, next_callback);
|
||||||
} else {
|
|
||||||
save_misc();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
function save_misc() {
|
function save_feature_config() {
|
||||||
MSP.send_message(MSPCodes.MSP_SET_MISC, mspHelper.crunch(MSPCodes.MSP_SET_MISC), false, save_3d);
|
var next_callback = save_board_alignment_config;
|
||||||
|
MSP.send_message(MSPCodes.MSP_SET_FEATURE_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FEATURE_CONFIG), false, next_callback);
|
||||||
}
|
}
|
||||||
|
|
||||||
function save_3d() {
|
function save_board_alignment_config() {
|
||||||
|
var next_callback = save_motor_config;
|
||||||
|
MSP.send_message(MSPCodes.MSP_SET_BOARD_ALIGNMENT_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BOARD_ALIGNMENT_CONFIG), false, next_callback);
|
||||||
|
}
|
||||||
|
|
||||||
|
function save_motor_config() {
|
||||||
|
var next_callback = save_motor_3d_config;
|
||||||
|
MSP.send_message(MSPCodes.MSP_SET_MOTOR_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_MOTOR_CONFIG), false, next_callback);
|
||||||
|
}
|
||||||
|
|
||||||
|
function save_motor_3d_config() {
|
||||||
var next_callback = save_rc_deadband;
|
var next_callback = save_rc_deadband;
|
||||||
if(semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
MSP.send_message(MSPCodes.MSP_SET_MOTOR_3D_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_MOTOR_3D_CONFIG), false, next_callback);
|
||||||
MSP.send_message(MSPCodes.MSP_SET_3D, mspHelper.crunch(MSPCodes.MSP_SET_3D), false, next_callback);
|
|
||||||
} else {
|
|
||||||
next_callback();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
function save_rc_deadband() {
|
function save_rc_deadband() {
|
||||||
var next_callback = save_sensor_alignment;
|
var next_callback = save_sensor_alignment;
|
||||||
if(semver.gte(CONFIG.apiVersion, "1.17.0")) {
|
|
||||||
MSP.send_message(MSPCodes.MSP_SET_RC_DEADBAND, mspHelper.crunch(MSPCodes.MSP_SET_RC_DEADBAND), false, next_callback);
|
MSP.send_message(MSPCodes.MSP_SET_RC_DEADBAND, mspHelper.crunch(MSPCodes.MSP_SET_RC_DEADBAND), false, next_callback);
|
||||||
} else {
|
|
||||||
next_callback();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
function save_sensor_alignment() {
|
function save_sensor_alignment() {
|
||||||
var next_callback = save_esc_protocol;
|
var next_callback = save_esc_protocol;
|
||||||
if(semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
|
||||||
MSP.send_message(MSPCodes.MSP_SET_SENSOR_ALIGNMENT, mspHelper.crunch(MSPCodes.MSP_SET_SENSOR_ALIGNMENT), false, next_callback);
|
MSP.send_message(MSPCodes.MSP_SET_SENSOR_ALIGNMENT, mspHelper.crunch(MSPCodes.MSP_SET_SENSOR_ALIGNMENT), false, next_callback);
|
||||||
} else {
|
|
||||||
next_callback();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
function save_esc_protocol() {
|
function save_esc_protocol() {
|
||||||
var next_callback = save_acc_trim;
|
var next_callback = save_acc_trim;
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
|
||||||
MSP.send_message(MSPCodes.MSP_SET_ADVANCED_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_ADVANCED_CONFIG), false, next_callback);
|
MSP.send_message(MSPCodes.MSP_SET_ADVANCED_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_ADVANCED_CONFIG), false, next_callback);
|
||||||
} else {
|
|
||||||
next_callback();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
function save_acc_trim() {
|
function save_acc_trim() {
|
||||||
MSP.send_message(MSPCodes.MSP_SET_ACC_TRIM, mspHelper.crunch(MSPCodes.MSP_SET_ACC_TRIM), false
|
var next_callback = save_arming_config;
|
||||||
, semver.gte(CONFIG.apiVersion, "1.8.0") ? save_arming_config : save_to_eeprom);
|
MSP.send_message(MSPCodes.MSP_SET_ACC_TRIM, mspHelper.crunch(MSPCodes.MSP_SET_ACC_TRIM), false, next_callback);
|
||||||
}
|
}
|
||||||
|
|
||||||
function save_arming_config() {
|
function save_arming_config() {
|
||||||
MSP.send_message(MSPCodes.MSP_SET_ARMING_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_ARMING_CONFIG), false, save_looptime_config);
|
MSP.send_message(MSPCodes.MSP_SET_ARMING_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_ARMING_CONFIG), false, save_sensor_config);
|
||||||
}
|
}
|
||||||
|
|
||||||
function save_looptime_config() {
|
|
||||||
var next_callback = save_sensor_config;
|
|
||||||
if (semver.lt(CONFIG.apiVersion, "1.16.0")) {
|
|
||||||
FC_CONFIG.loopTime = PID_ADVANCED_CONFIG.gyro_sync_denom * 125;
|
|
||||||
MSP.send_message(MSPCodes.MSP_SET_LOOP_TIME, mspHelper.crunch(MSPCodes.MSP_SET_LOOP_TIME), false, next_callback);
|
|
||||||
} else {
|
|
||||||
next_callback();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
function save_sensor_config() {
|
function save_sensor_config() {
|
||||||
var next_callback = save_name;
|
var next_callback = save_name;
|
||||||
|
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
|
||||||
SENSOR_CONFIG.acc_hardware = $('input[id="accHardwareSwitch"]').is(':checked') ? 0 : 1;
|
SENSOR_CONFIG.acc_hardware = $('input[id="accHardwareSwitch"]').is(':checked') ? 0 : 1;
|
||||||
SENSOR_CONFIG.baro_hardware = $('input[id="baroHardwareSwitch"]').is(':checked') ? 0 : 1;
|
SENSOR_CONFIG.baro_hardware = $('input[id="baroHardwareSwitch"]').is(':checked') ? 0 : 1;
|
||||||
SENSOR_CONFIG.mag_hardware = $('input[id="magHardwareSwitch"]').is(':checked') ? 0 : 1;
|
SENSOR_CONFIG.mag_hardware = $('input[id="magHardwareSwitch"]').is(':checked') ? 0 : 1;
|
||||||
MSP.send_message(MSPCodes.MSP_SET_SENSOR_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_SENSOR_CONFIG), false, next_callback);
|
MSP.send_message(MSPCodes.MSP_SET_SENSOR_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_SENSOR_CONFIG), false, next_callback);
|
||||||
} else {
|
|
||||||
next_callback();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
function save_name() {
|
function save_name() {
|
||||||
var next_callback = save_battery;
|
var next_callback = save_rx_config;
|
||||||
|
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
CONFIG.name = $.trim($('input[name="craftName"]').val());
|
||||||
CONFIG.name = $.trim($('input[name="vesselName"]').val());
|
|
||||||
MSP.send_message(MSPCodes.MSP_SET_NAME, mspHelper.crunch(MSPCodes.MSP_SET_NAME), false, next_callback);
|
MSP.send_message(MSPCodes.MSP_SET_NAME, mspHelper.crunch(MSPCodes.MSP_SET_NAME), false, next_callback);
|
||||||
|
}
|
||||||
|
|
||||||
|
function save_rx_config() {
|
||||||
|
var next_callback = save_battery;
|
||||||
|
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||||
|
MSP.send_message(MSPCodes.MSP_SET_RX_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_RX_CONFIG), false, next_callback);
|
||||||
} else {
|
} else {
|
||||||
next_callback();
|
next_callback();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
function save_battery() {
|
function save_battery() {
|
||||||
var next_callback = save_current;
|
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
|
||||||
MSP.send_message(MSPCodes.MSP_SET_VOLTAGE_METER_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_VOLTAGE_METER_CONFIG), false, next_callback);
|
|
||||||
} else {
|
|
||||||
next_callback();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
function save_current() {
|
|
||||||
var next_callback = save_rx_config;
|
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
|
||||||
MSP.send_message(MSPCodes.MSP_SET_CURRENT_METER_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_CURRENT_METER_CONFIG), false, next_callback);
|
|
||||||
} else {
|
|
||||||
next_callback();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
function save_rx_config() {
|
|
||||||
var next_callback = save_to_eeprom;
|
var next_callback = save_to_eeprom;
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.31.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.33.0")) {
|
||||||
MSP.send_message(MSPCodes.MSP_SET_RX_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_RX_CONFIG), false, next_callback);
|
MSP.send_message(MSPCodes.MSP_SET_BATTERY_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BATTERY_CONFIG), false, next_callback);
|
||||||
} else {
|
} else {
|
||||||
next_callback();
|
next_callback();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// FIXME voltage/current configuation saving not implemented for >= 1.33.0 and broken/disabled for <= 1.33.0
|
||||||
|
|
||||||
|
// function save_voltage() {
|
||||||
|
// var next_callback = save_current;
|
||||||
|
// if (semver.lt(CONFIG.apiVersion, "1.33.0")) {
|
||||||
|
// MSP.send_message(MSPCodes.MSP_SET_VOLTAGE_METER_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_VOLTAGE_METER_CONFIG), false, next_callback);
|
||||||
|
// } else {
|
||||||
|
// next_callback();
|
||||||
|
// }
|
||||||
|
// }
|
||||||
|
//
|
||||||
|
// function save_current() {
|
||||||
|
// var next_callback = save_to_eeprom;
|
||||||
|
// if (semver.gte(CONFIG.apiVersion, "1.33.0")) {
|
||||||
|
// MSP.send_message(MSPCodes.MSP_SET_CURRENT_METER_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_CURRENT_METER_CONFIG), false, next_callback);
|
||||||
|
// } else {
|
||||||
|
// next_callback();
|
||||||
|
// }
|
||||||
|
// }
|
||||||
|
|
||||||
|
|
||||||
function save_to_eeprom() {
|
function save_to_eeprom() {
|
||||||
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, reboot);
|
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, reboot);
|
||||||
}
|
}
|
||||||
|
@ -907,8 +923,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
MSP.send_message(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG), false, save_serial_config);
|
save_serial_config();
|
||||||
|
|
||||||
});
|
});
|
||||||
|
|
||||||
// status data pulled via separate timer with static speed
|
// status data pulled via separate timer with static speed
|
||||||
|
|
|
@ -4,37 +4,14 @@
|
||||||
<div class="cf_doc_version_bt">
|
<div class="cf_doc_version_bt">
|
||||||
<a id="button-documentation" href="https://github.com/betaflight/betaflight/releases" target="_blank"></a>
|
<a id="button-documentation" href="https://github.com/betaflight/betaflight/releases" target="_blank"></a>
|
||||||
</div>
|
</div>
|
||||||
<div class="note newpane">
|
<div class="note">
|
||||||
<div class="note_spacer">
|
<div class="note_spacer">
|
||||||
<p i18n="failsafeFeaturesHelpNew"></p>
|
<p i18n="failsafeFeaturesHelpNew"></p>
|
||||||
</p>
|
</p>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="note oldpane">
|
|
||||||
<div class="note_spacer">
|
|
||||||
<p i18n="failsafeFeaturesHelpOld"></p>
|
|
||||||
</p>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<div class="leftWrapper">
|
<div class="leftWrapper">
|
||||||
<div class="gui_box grey oldpane">
|
<div class="gui_box grey">
|
||||||
<div class="gui_box_titlebar">
|
|
||||||
<div class="spacer_box_title" i18n="failsafePaneTitleOld"></div>
|
|
||||||
</div>
|
|
||||||
<div class="spacer_box">
|
|
||||||
<table>
|
|
||||||
<tbody class="featuresOld rxFailsafe">
|
|
||||||
<!-- table generated here -->
|
|
||||||
</tbody>
|
|
||||||
</table>
|
|
||||||
<div class="number">
|
|
||||||
<label> <input type="number" name="failsafe_throttle_old" min="0" max="2000" /> <span
|
|
||||||
i18n="failsafeThrottleItemOld"></span>
|
|
||||||
</label>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<div class="gui_box grey newpane">
|
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title" i18n="failsafePulsrangeTitle"></div>
|
<div class="spacer_box_title" i18n="failsafePulsrangeTitle"></div>
|
||||||
<div class="helpicon cf_tip" i18n_title="failsafePulsrangeHelp"></div>
|
<div class="helpicon cf_tip" i18n_title="failsafePulsrangeHelp"></div>
|
||||||
|
@ -52,7 +29,7 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="gui_box grey stage1 newpane">
|
<div class="gui_box grey stage1">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title" i18n="failsafeChannelFallbackSettingsTitle"></div>
|
<div class="spacer_box_title" i18n="failsafeChannelFallbackSettingsTitle"></div>
|
||||||
<div class="helpicon cf_tip" i18n_title="failsafeChannelFallbackSettingsHelp"></div>
|
<div class="helpicon cf_tip" i18n_title="failsafeChannelFallbackSettingsHelp"></div>
|
||||||
|
@ -65,7 +42,7 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="rightWrapper">
|
<div class="rightWrapper">
|
||||||
<div class="gui_box grey newpane">
|
<div class="gui_box grey">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title" i18n="failsafeStageTwoSettingsTitle"></div>
|
<div class="spacer_box_title" i18n="failsafeStageTwoSettingsTitle"></div>
|
||||||
</div>
|
</div>
|
||||||
|
|
|
@ -34,33 +34,31 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function get_rc_data() {
|
function get_rc_data() {
|
||||||
MSP.send_message(MSPCodes.MSP_RC, false, false, load_config);
|
MSP.send_message(MSPCodes.MSP_RC, false, false, load_feature_config);
|
||||||
}
|
}
|
||||||
|
|
||||||
// BEGIN Support for pre API version 1.15.0
|
function load_feature_config() {
|
||||||
function load_config() {
|
MSP.send_message(MSPCodes.MSP_FEATURE_CONFIG, false, false, load_motor_config);
|
||||||
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, load_misc);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_misc() {
|
function load_motor_config() {
|
||||||
MSP.send_message(MSPCodes.MSP_MISC, false, false, load_html);
|
MSP.send_message(MSPCodes.MSP_MOTOR_CONFIG, false, false, load_compass_config);
|
||||||
|
}
|
||||||
|
|
||||||
|
function load_compass_config() {
|
||||||
|
MSP.send_message(MSPCodes.MSP_COMPASS_CONFIG, false, false, load_gps_config);
|
||||||
|
}
|
||||||
|
|
||||||
|
function load_gps_config() {
|
||||||
|
MSP.send_message(MSPCodes.MSP_GPS_CONFIG, false, false, load_html);
|
||||||
}
|
}
|
||||||
// END (Support for pre API version 1.15.0
|
|
||||||
|
|
||||||
function load_html() {
|
function load_html() {
|
||||||
$('#content').load("./tabs/failsafe.html", process_html);
|
$('#content').load("./tabs/failsafe.html", process_html);
|
||||||
}
|
}
|
||||||
|
|
||||||
var apiVersionGte1_15_0 = semver.gte(CONFIG.apiVersion, "1.15.0");
|
|
||||||
|
|
||||||
// Uncomment next line for testing older functionality on newer API version
|
|
||||||
//apiVersionGte1_15_0 = false;
|
|
||||||
|
|
||||||
if(apiVersionGte1_15_0) {
|
|
||||||
load_rx_config();
|
load_rx_config();
|
||||||
} else {
|
|
||||||
load_config();
|
|
||||||
}
|
|
||||||
|
|
||||||
function process_html() {
|
function process_html() {
|
||||||
// fill stage 2 fields
|
// fill stage 2 fields
|
||||||
|
@ -72,18 +70,11 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Conditionally hide the old or the new control pane's
|
// FIXME cleanup oldpane html and css
|
||||||
if(apiVersionGte1_15_0) {
|
|
||||||
var oldPane = $('div.oldpane');
|
var oldPane = $('div.oldpane');
|
||||||
oldPane.prop("disabled", true);
|
oldPane.prop("disabled", true);
|
||||||
oldPane.hide();
|
oldPane.hide();
|
||||||
} else {
|
|
||||||
var newPane = $('div.newpane');
|
|
||||||
newPane.prop("disabled", true);
|
|
||||||
newPane.hide();
|
|
||||||
}
|
|
||||||
|
|
||||||
if (apiVersionGte1_15_0) {
|
|
||||||
// generate labels for assigned aux modes
|
// generate labels for assigned aux modes
|
||||||
var auxAssignment = [],
|
var auxAssignment = [],
|
||||||
i,
|
i,
|
||||||
|
@ -153,7 +144,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
||||||
<option value="2">Set</option>\
|
<option value="2">Set</option>\
|
||||||
</select>\
|
</select>\
|
||||||
</div>\
|
</div>\
|
||||||
<div class="auxiliary"><input type="number" name="aux_value" min="750" max="2250" id="' + i + '"/></div>\
|
<div class="auxiliary"><input type="number" name="aux_value" min="750" max="2250" step="25" id="' + i + '"/></div>\
|
||||||
</div>\
|
</div>\
|
||||||
');
|
');
|
||||||
}
|
}
|
||||||
|
@ -208,13 +199,13 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
||||||
channel_mode_array[i].change();
|
channel_mode_array[i].change();
|
||||||
}
|
}
|
||||||
|
|
||||||
BF_CONFIG.features.generateElements($('.tab-failsafe .featuresNew'));
|
FEATURE_CONFIG.features.generateElements($('.tab-failsafe .featuresNew'));
|
||||||
|
|
||||||
var failsafeFeature = $('input[name="FAILSAFE"]');
|
var failsafeFeature = $('input[name="FAILSAFE"]');
|
||||||
failsafeFeature.change(function () {
|
failsafeFeature.change(function () {
|
||||||
toggleStage2($(this).is(':checked'));
|
toggleStage2($(this).is(':checked'));
|
||||||
});
|
});
|
||||||
toggleStage2(BF_CONFIG.features.isEnabled('FAILSAFE'));
|
toggleStage2(FEATURE_CONFIG.features.isEnabled('FAILSAFE'));
|
||||||
|
|
||||||
$('input[name="failsafe_throttle"]').val(FAILSAFE_CONFIG.failsafe_throttle);
|
$('input[name="failsafe_throttle"]').val(FAILSAFE_CONFIG.failsafe_throttle);
|
||||||
$('input[name="failsafe_off_delay"]').val(FAILSAFE_CONFIG.failsafe_off_delay);
|
$('input[name="failsafe_off_delay"]').val(FAILSAFE_CONFIG.failsafe_off_delay);
|
||||||
|
@ -260,18 +251,12 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
||||||
// set stage 2 kill switch option
|
// set stage 2 kill switch option
|
||||||
$('input[name="failsafe_kill_switch"]').prop('checked', FAILSAFE_CONFIG.failsafe_kill_switch);
|
$('input[name="failsafe_kill_switch"]').prop('checked', FAILSAFE_CONFIG.failsafe_kill_switch);
|
||||||
|
|
||||||
} else {
|
|
||||||
BF_CONFIG.features.generateElements($('.tab-failsafe .featuresOld'));
|
|
||||||
// fill failsafe_throttle field (pre API 1.15.0)
|
|
||||||
$('input[name="failsafe_throttle_old"]').val(MISC.failsafe_throttle);
|
|
||||||
}
|
|
||||||
|
|
||||||
$('a.save').click(function () {
|
$('a.save').click(function () {
|
||||||
// gather data that doesn't have automatic change event bound
|
// gather data that doesn't have automatic change event bound
|
||||||
|
|
||||||
BF_CONFIG.features.updateData($('input[name="FAILSAFE"]'));
|
FEATURE_CONFIG.features.updateData($('input[name="FAILSAFE"]'));
|
||||||
|
|
||||||
if(apiVersionGte1_15_0) {
|
|
||||||
RX_CONFIG.rx_min_usec = parseInt($('input[name="rx_min_usec"]').val());
|
RX_CONFIG.rx_min_usec = parseInt($('input[name="rx_min_usec"]').val());
|
||||||
RX_CONFIG.rx_max_usec = parseInt($('input[name="rx_max_usec"]').val());
|
RX_CONFIG.rx_max_usec = parseInt($('input[name="rx_max_usec"]').val());
|
||||||
|
|
||||||
|
@ -287,29 +272,19 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
|
|
||||||
FAILSAFE_CONFIG.failsafe_kill_switch = $('input[name="failsafe_kill_switch"]').is(':checked') ? 1 : 0;
|
FAILSAFE_CONFIG.failsafe_kill_switch = $('input[name="failsafe_kill_switch"]').is(':checked') ? 1 : 0;
|
||||||
} else {
|
|
||||||
// get failsafe_throttle field value (pre API 1.15.0)
|
|
||||||
MISC.failsafe_throttle = parseInt($('input[name="failsafe_throttle_old"]').val());
|
|
||||||
}
|
|
||||||
|
|
||||||
function save_failssafe_config() {
|
function save_failssafe_config() {
|
||||||
MSP.send_message(MSPCodes.MSP_SET_FAILSAFE_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FAILSAFE_CONFIG), false, save_rxfail_config);
|
MSP.send_message(MSPCodes.MSP_SET_FAILSAFE_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FAILSAFE_CONFIG), false, save_rxfail_config);
|
||||||
}
|
}
|
||||||
|
|
||||||
function save_rxfail_config() {
|
function save_rxfail_config() {
|
||||||
mspHelper.sendRxFailConfig(save_bf_config);
|
mspHelper.sendRxFailConfig(save_feature_config);
|
||||||
}
|
}
|
||||||
|
|
||||||
function save_bf_config() {
|
function save_feature_config() {
|
||||||
MSP.send_message(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG), false, save_to_eeprom);
|
MSP.send_message(MSPCodes.MSP_SET_FEATURE_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FEATURE_CONFIG), false, save_to_eeprom);
|
||||||
}
|
}
|
||||||
|
|
||||||
// BEGIN pre API 1.15.0 save functions
|
|
||||||
function save_misc() {
|
|
||||||
MSP.send_message(MSPCodes.MSP_SET_MISC, mspHelper.crunch(MSPCodes.MSP_SET_MISC), false, save_to_eeprom);
|
|
||||||
}
|
|
||||||
// END pre API 1.15.0 save functions
|
|
||||||
|
|
||||||
function save_to_eeprom() {
|
function save_to_eeprom() {
|
||||||
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, reboot);
|
MSP.send_message(MSPCodes.MSP_EEPROM_WRITE, false, false, reboot);
|
||||||
}
|
}
|
||||||
|
@ -341,11 +316,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if(apiVersionGte1_15_0) {
|
|
||||||
MSP.send_message(MSPCodes.MSP_SET_RX_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_RX_CONFIG), false, save_failssafe_config);
|
MSP.send_message(MSPCodes.MSP_SET_RX_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_RX_CONFIG), false, save_failssafe_config);
|
||||||
} else {
|
|
||||||
MSP.send_message(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG), false, save_misc);
|
|
||||||
}
|
|
||||||
});
|
});
|
||||||
|
|
||||||
// translate to user-selected language
|
// translate to user-selected language
|
||||||
|
|
|
@ -229,8 +229,18 @@ TABS.logging.initialize = function (callback) {
|
||||||
fileWriter = null;
|
fileWriter = null;
|
||||||
|
|
||||||
function prepare_file() {
|
function prepare_file() {
|
||||||
|
|
||||||
|
var prefix = CONFIG.flightControllerIdentifier + '_log';
|
||||||
|
var suffix = 'csv';
|
||||||
|
|
||||||
|
var filename = generateFilename(prefix, suffix);
|
||||||
|
|
||||||
|
var accepts = [{
|
||||||
|
extensions: [suffix],
|
||||||
|
}];
|
||||||
|
|
||||||
// create or load the file
|
// create or load the file
|
||||||
chrome.fileSystem.chooseEntry({type: 'saveFile', suggestedName: 'betaflight_data_log', accepts: [{extensions: ['csv']}]}, function(entry) {
|
chrome.fileSystem.chooseEntry({type: 'saveFile', suggestedName: filename, accepts: accepts}, function(entry) {
|
||||||
if (!entry) {
|
if (!entry) {
|
||||||
console.log('No file selected');
|
console.log('No file selected');
|
||||||
return;
|
return;
|
||||||
|
|
|
@ -12,40 +12,29 @@ TABS.motors.initialize = function (callback) {
|
||||||
self.armed = false;
|
self.armed = false;
|
||||||
self.feature3DSupported = false;
|
self.feature3DSupported = false;
|
||||||
self.allowTestMode = true;
|
self.allowTestMode = true;
|
||||||
|
self.feature3DSupported = true;
|
||||||
|
|
||||||
if (GUI.active_tab != 'motors') {
|
if (GUI.active_tab != 'motors') {
|
||||||
GUI.active_tab = 'motors';
|
GUI.active_tab = 'motors';
|
||||||
}
|
}
|
||||||
|
|
||||||
function get_arm_status() {
|
function get_arm_status() {
|
||||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false, load_config);
|
MSP.send_message(MSPCodes.MSP_STATUS, false, false, load_feature_config);
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_config() {
|
function load_feature_config() {
|
||||||
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, load_3d);
|
MSP.send_message(MSPCodes.MSP_FEATURE_CONFIG, false, false, load_motor_3d_config);
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_3d() {
|
function load_motor_3d_config() {
|
||||||
var next_callback = esc_protocol;
|
MSP.send_message(MSPCodes.MSP_MOTOR_3D_CONFIG, false, false, load_esc_protocol);
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
|
|
||||||
self.feature3DSupported = true;
|
|
||||||
MSP.send_message(MSPCodes.MSP_3D, false, false, next_callback);
|
|
||||||
} else {
|
|
||||||
next_callback();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
function esc_protocol() {
|
function load_esc_protocol() {
|
||||||
var next_callback = get_motor_data;
|
MSP.send_message(MSPCodes.MSP_ADVANCED_CONFIG, false, false, load_motor_data);
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
|
||||||
MSP.send_message(MSPCodes.MSP_ADVANCED_CONFIG, false, false, next_callback);
|
|
||||||
} else {
|
|
||||||
next_callback();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
function get_motor_data() {
|
function load_motor_data() {
|
||||||
update_arm_status();
|
|
||||||
MSP.send_message(MSPCodes.MSP_MOTOR, false, false, load_html);
|
MSP.send_message(MSPCodes.MSP_MOTOR, false, false, load_html);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -53,7 +42,7 @@ TABS.motors.initialize = function (callback) {
|
||||||
$('#content').load("./tabs/motors.html", process_html);
|
$('#content').load("./tabs/motors.html", process_html);
|
||||||
}
|
}
|
||||||
|
|
||||||
MSP.send_message(MSPCodes.MSP_MISC, false, false, get_arm_status);
|
MSP.send_message(MSPCodes.MSP_MOTOR_CONFIG, false, false, get_arm_status);
|
||||||
|
|
||||||
function update_arm_status() {
|
function update_arm_status() {
|
||||||
self.armed = bit_check(CONFIG.mode, 0);
|
self.armed = bit_check(CONFIG.mode, 0);
|
||||||
|
@ -186,7 +175,9 @@ TABS.motors.initialize = function (callback) {
|
||||||
// translate to user-selected language
|
// translate to user-selected language
|
||||||
localize();
|
localize();
|
||||||
|
|
||||||
self.feature3DEnabled = BF_CONFIG.features.isEnabled('3D');
|
update_arm_status();
|
||||||
|
|
||||||
|
self.feature3DEnabled = FEATURE_CONFIG.features.isEnabled('3D');
|
||||||
|
|
||||||
if (self.feature3DEnabled && !self.feature3DSupported) {
|
if (self.feature3DEnabled && !self.feature3DSupported) {
|
||||||
self.allowTestMode = false;
|
self.allowTestMode = false;
|
||||||
|
@ -201,7 +192,7 @@ TABS.motors.initialize = function (callback) {
|
||||||
$('#motorsEnableTestMode').prop('checked', false)
|
$('#motorsEnableTestMode').prop('checked', false)
|
||||||
.prop('disabled', true);
|
.prop('disabled', true);
|
||||||
|
|
||||||
update_model(BF_CONFIG.mixerConfiguration);
|
update_model(MIXER_CONFIG.mixer);
|
||||||
|
|
||||||
// Always start with default/empty sensor data array, clean slate all
|
// Always start with default/empty sensor data array, clean slate all
|
||||||
initSensorData();
|
initSensorData();
|
||||||
|
@ -330,19 +321,19 @@ TABS.motors.initialize = function (callback) {
|
||||||
');
|
');
|
||||||
}
|
}
|
||||||
|
|
||||||
$('div.sliders input').prop('min', MISC.mincommand)
|
$('div.sliders input').prop('min', MOTOR_CONFIG.mincommand)
|
||||||
.prop('max', MISC.maxthrottle);
|
.prop('max', MOTOR_CONFIG.maxthrottle);
|
||||||
$('div.values li:not(:last)').text(MISC.mincommand);
|
$('div.values li:not(:last)').text(MOTOR_CONFIG.mincommand);
|
||||||
|
|
||||||
if(self.feature3DEnabled && self.feature3DSupported) {
|
if(self.feature3DEnabled && self.feature3DSupported) {
|
||||||
//Arbitrary sanity checks
|
//Arbitrary sanity checks
|
||||||
//Note: values may need to be revisited
|
//Note: values may need to be revisited
|
||||||
if(_3D.neutral3d > 1575 || _3D.neutral3d < 1425)
|
if(MOTOR_3D_CONFIG.neutral > 1575 || MOTOR_3D_CONFIG.neutral < 1425)
|
||||||
_3D.neutral3d = 1500;
|
MOTOR_3D_CONFIG.neutral = 1500;
|
||||||
|
|
||||||
$('div.sliders input').val(_3D.neutral3d);
|
$('div.sliders input').val(MOTOR_3D_CONFIG.neutral);
|
||||||
} else {
|
} else {
|
||||||
$('div.sliders input').val(MISC.mincommand);
|
$('div.sliders input').val(MOTOR_CONFIG.mincommand);
|
||||||
}
|
}
|
||||||
|
|
||||||
if(self.allowTestMode){
|
if(self.allowTestMode){
|
||||||
|
@ -397,9 +388,9 @@ TABS.motors.initialize = function (callback) {
|
||||||
|
|
||||||
// change all values to default
|
// change all values to default
|
||||||
if (self.feature3DEnabled && self.feature3DSupported) {
|
if (self.feature3DEnabled && self.feature3DSupported) {
|
||||||
$('div.sliders input').val(_3D.neutral3d);
|
$('div.sliders input').val(MOTOR_3D_CONFIG.neutral);
|
||||||
} else {
|
} else {
|
||||||
$('div.sliders input').val(MISC.mincommand);
|
$('div.sliders input').val(MOTOR_CONFIG.mincommand);
|
||||||
}
|
}
|
||||||
|
|
||||||
$('div.sliders input').trigger('input');
|
$('div.sliders input').trigger('input');
|
||||||
|
@ -411,11 +402,11 @@ TABS.motors.initialize = function (callback) {
|
||||||
|
|
||||||
for (var i = 0; i < number_of_valid_outputs; i++) {
|
for (var i = 0; i < number_of_valid_outputs; i++) {
|
||||||
if (!self.feature3DEnabled) {
|
if (!self.feature3DEnabled) {
|
||||||
if (MOTOR_DATA[i] > MISC.mincommand) {
|
if (MOTOR_DATA[i] > MOTOR_CONFIG.mincommand) {
|
||||||
motors_running = true;
|
motors_running = true;
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
if ((MOTOR_DATA[i] < _3D.deadband3d_low) || (MOTOR_DATA[i] > _3D.deadband3d_high)) {
|
if ((MOTOR_DATA[i] < MOTOR_3D_CONFIG.deadband3d_low) || (MOTOR_DATA[i] > MOTOR_3D_CONFIG.deadband3d_high)) {
|
||||||
motors_running = true;
|
motors_running = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -473,8 +464,8 @@ TABS.motors.initialize = function (callback) {
|
||||||
full_block_scale = 1000;
|
full_block_scale = 1000;
|
||||||
motorOffset = 1000;
|
motorOffset = 1000;
|
||||||
} else {
|
} else {
|
||||||
full_block_scale = MISC.maxthrottle - MISC.mincommand;
|
full_block_scale = MOTOR_CONFIG.maxthrottle - MOTOR_CONFIG.mincommand;
|
||||||
motorOffset = MISC.mincommand;
|
motorOffset = MOTOR_CONFIG.mincommand;
|
||||||
}
|
}
|
||||||
|
|
||||||
function update_ui() {
|
function update_ui() {
|
||||||
|
|
|
@ -4,7 +4,6 @@ var
|
||||||
sdcardTimer;
|
sdcardTimer;
|
||||||
|
|
||||||
TABS.onboard_logging = {
|
TABS.onboard_logging = {
|
||||||
available: false,
|
|
||||||
blockSize: 128,
|
blockSize: 128,
|
||||||
|
|
||||||
BLOCK_SIZE: 4096,
|
BLOCK_SIZE: 4096,
|
||||||
|
@ -21,39 +20,17 @@ TABS.onboard_logging.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
if (CONFIGURATOR.connectionValid) {
|
if (CONFIGURATOR.connectionValid) {
|
||||||
// Blackbox was introduced in 1.5.0, dataflash API was introduced in 1.8.0, BLACKBOX/SDCARD MSP APIs in 1.11.0
|
|
||||||
TABS.onboard_logging.available = semver.gte(CONFIG.flightControllerVersion, "1.5.0");
|
|
||||||
|
|
||||||
if (!TABS.onboard_logging.available) {
|
MSP.send_message(MSPCodes.MSP_FEATURE_CONFIG, false, false, function() {
|
||||||
load_html();
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
var load_name = function () {
|
|
||||||
var next_callback = load_html;
|
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
|
||||||
MSP.send_message(MSPCodes.MSP_NAME, false, false, next_callback);
|
|
||||||
} else {
|
|
||||||
next_callback();
|
|
||||||
}
|
|
||||||
};
|
|
||||||
|
|
||||||
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, function() {
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.8.0")) {
|
|
||||||
MSP.send_message(MSPCodes.MSP_DATAFLASH_SUMMARY, false, false, function() {
|
MSP.send_message(MSPCodes.MSP_DATAFLASH_SUMMARY, false, false, function() {
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.11.0")) {
|
|
||||||
MSP.send_message(MSPCodes.MSP_SDCARD_SUMMARY, false, false, function() {
|
MSP.send_message(MSPCodes.MSP_SDCARD_SUMMARY, false, false, function() {
|
||||||
MSP.send_message(MSPCodes.MSP_BLACKBOX_CONFIG, false, false, function() {
|
MSP.send_message(MSPCodes.MSP_BLACKBOX_CONFIG, false, false, function() {
|
||||||
MSP.send_message(MSPCodes.MSP_ADVANCED_CONFIG, false, false, load_name);
|
MSP.send_message(MSPCodes.MSP_ADVANCED_CONFIG, false, false, function() {
|
||||||
|
MSP.send_message(MSPCodes.MSP_NAME, false, false, load_html);
|
||||||
|
});
|
||||||
});
|
});
|
||||||
});
|
});
|
||||||
} else {
|
|
||||||
load_html();
|
|
||||||
}
|
|
||||||
});
|
});
|
||||||
} else {
|
|
||||||
load_html();
|
|
||||||
}
|
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -109,11 +86,8 @@ TABS.onboard_logging.initialize = function (callback) {
|
||||||
*
|
*
|
||||||
* The best we can do on those targets is check the BLACKBOX feature bit to identify support for Blackbox instead.
|
* The best we can do on those targets is check the BLACKBOX feature bit to identify support for Blackbox instead.
|
||||||
*/
|
*/
|
||||||
if (BLACKBOX.supported || DATAFLASH.supported
|
if ((BLACKBOX.supported || DATAFLASH.supported) && FEATURE_CONFIG.features.isEnabled('BLACKBOX')) {
|
||||||
|| semver.gte(CONFIG.flightControllerVersion, "1.5.0") && semver.lte(CONFIG.flightControllerVersion, "1.10.0") && BF_CONFIG.features.isEnabled('BLACKBOX')) {
|
|
||||||
blackboxSupport = 'yes';
|
blackboxSupport = 'yes';
|
||||||
} else if (semver.gte(CONFIG.flightControllerVersion, "1.5.0") && semver.lte(CONFIG.flightControllerVersion, "1.10.0")) {
|
|
||||||
blackboxSupport = 'maybe';
|
|
||||||
} else {
|
} else {
|
||||||
blackboxSupport = 'no';
|
blackboxSupport = 'no';
|
||||||
}
|
}
|
||||||
|
|
|
@ -34,19 +34,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
}).then(function() {
|
}).then(function() {
|
||||||
return MSP.promise(MSPCodes.MSP_FILTER_CONFIG);
|
return MSP.promise(MSPCodes.MSP_FILTER_CONFIG);
|
||||||
}).then(function() {
|
}).then(function() {
|
||||||
var promise = true;
|
return MSP.promise(MSPCodes.MSP_RC_DEADBAND);
|
||||||
if (CONFIG.flightControllerIdentifier === "BTFL" && semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
|
||||||
promise = MSP.promise(MSPCodes.MSP_BF_CONFIG);
|
|
||||||
}
|
|
||||||
|
|
||||||
return promise;
|
|
||||||
}).then(function() {
|
|
||||||
var promise = true;
|
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
|
||||||
promise = MSP.promise(MSPCodes.MSP_RC_DEADBAND);
|
|
||||||
}
|
|
||||||
|
|
||||||
return promise;
|
|
||||||
}).then(function() {
|
}).then(function() {
|
||||||
$('#content').load("./tabs/pid_tuning.html", process_html);
|
$('#content').load("./tabs/pid_tuning.html", process_html);
|
||||||
});
|
});
|
||||||
|
@ -236,7 +224,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")
|
if (semver.gte(CONFIG.apiVersion, "1.20.0")
|
||||||
|| semver.gte(CONFIG.apiVersion, "1.16.0") && BF_CONFIG.features.isEnabled('SUPEREXPO_RATES')) {
|
|| semver.gte(CONFIG.apiVersion, "1.16.0") && FEATURE_CONFIG.features.isEnabled('SUPEREXPO_RATES')) {
|
||||||
$('#pid-tuning .rate').text(chrome.i18n.getMessage("pidTuningSuperRate"));
|
$('#pid-tuning .rate').text(chrome.i18n.getMessage("pidTuningSuperRate"));
|
||||||
} else {
|
} else {
|
||||||
$('#pid-tuning .rate').text(chrome.i18n.getMessage("pidTuningRate"));
|
$('#pid-tuning .rate').text(chrome.i18n.getMessage("pidTuningRate"));
|
||||||
|
@ -351,7 +339,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
FILTER_CONFIG.yaw_lpf_hz = parseInt($('.pid_filter input[name="yawLowpassFrequency"]').val());
|
FILTER_CONFIG.yaw_lpf_hz = parseInt($('.pid_filter input[name="yawLowpassFrequency"]').val());
|
||||||
|
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.16.0") && !semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.16.0") && !semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||||
BF_CONFIG.features.updateData($('input[name="SUPEREXPO_RATES"]'));
|
FEATURE_CONFIG.features.updateData($('input[name="SUPEREXPO_RATES"]'));
|
||||||
}
|
}
|
||||||
|
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||||
|
@ -407,7 +395,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
$('#pid_mag').show();
|
$('#pid_mag').show();
|
||||||
showTitle = true;
|
showTitle = true;
|
||||||
}
|
}
|
||||||
if (BF_CONFIG.features.isEnabled('GPS')) {
|
if (FEATURE_CONFIG.features.isEnabled('GPS')) {
|
||||||
$('#pid_gps').show();
|
$('#pid_gps').show();
|
||||||
showTitle = true;
|
showTitle = true;
|
||||||
}
|
}
|
||||||
|
@ -470,7 +458,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
|
|
||||||
function process_html() {
|
function process_html() {
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.16.0") && !semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.16.0") && !semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||||
BF_CONFIG.features.generateElements($('.tab-pid_tuning .features'));
|
FEATURE_CONFIG.features.generateElements($('.tab-pid_tuning .features'));
|
||||||
} else {
|
} else {
|
||||||
$('.tab-pid_tuning .pidTuningFeatures').hide();
|
$('.tab-pid_tuning .pidTuningFeatures').hide();
|
||||||
}
|
}
|
||||||
|
@ -487,9 +475,9 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
rc_rate_yaw: RC_tuning.rcYawRate,
|
rc_rate_yaw: RC_tuning.rcYawRate,
|
||||||
rc_expo: RC_tuning.RC_EXPO,
|
rc_expo: RC_tuning.RC_EXPO,
|
||||||
rc_yaw_expo: RC_tuning.RC_YAW_EXPO,
|
rc_yaw_expo: RC_tuning.RC_YAW_EXPO,
|
||||||
superexpo: BF_CONFIG.features.isEnabled('SUPEREXPO_RATES'),
|
superexpo: FEATURE_CONFIG.features.isEnabled('SUPEREXPO_RATES'),
|
||||||
deadband: RC_deadband.deadband,
|
deadband: RC_DEADBAND_CONFIG.deadband,
|
||||||
yawDeadband: RC_deadband.yaw_deadband
|
yawDeadband: RC_DEADBAND_CONFIG.yaw_deadband
|
||||||
};
|
};
|
||||||
|
|
||||||
if (semver.lt(CONFIG.apiVersion, "1.7.0")) {
|
if (semver.lt(CONFIG.apiVersion, "1.7.0")) {
|
||||||
|
@ -853,19 +841,11 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
}).then(function () {
|
}).then(function () {
|
||||||
return MSP.promise(MSPCodes.MSP_SET_PID, mspHelper.crunch(MSPCodes.MSP_SET_PID));
|
return MSP.promise(MSPCodes.MSP_SET_PID, mspHelper.crunch(MSPCodes.MSP_SET_PID));
|
||||||
}).then(function () {
|
}).then(function () {
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
|
||||||
return MSP.promise(MSPCodes.MSP_SET_PID_ADVANCED, mspHelper.crunch(MSPCodes.MSP_SET_PID_ADVANCED));
|
return MSP.promise(MSPCodes.MSP_SET_PID_ADVANCED, mspHelper.crunch(MSPCodes.MSP_SET_PID_ADVANCED));
|
||||||
}
|
|
||||||
}).then(function () {
|
}).then(function () {
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
|
||||||
return MSP.promise(MSPCodes.MSP_SET_FILTER_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FILTER_CONFIG));
|
return MSP.promise(MSPCodes.MSP_SET_FILTER_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FILTER_CONFIG));
|
||||||
}
|
|
||||||
}).then(function () {
|
}).then(function () {
|
||||||
return MSP.promise(MSPCodes.MSP_SET_RC_TUNING, mspHelper.crunch(MSPCodes.MSP_SET_RC_TUNING));
|
return MSP.promise(MSPCodes.MSP_SET_RC_TUNING, mspHelper.crunch(MSPCodes.MSP_SET_RC_TUNING));
|
||||||
}).then(function () {
|
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
|
||||||
return MSP.promise(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG));
|
|
||||||
}
|
|
||||||
}).then(function () {
|
}).then(function () {
|
||||||
return MSP.promise(MSPCodes.MSP_EEPROM_WRITE);
|
return MSP.promise(MSPCodes.MSP_EEPROM_WRITE);
|
||||||
}).then(function () {
|
}).then(function () {
|
||||||
|
|
|
@ -164,6 +164,7 @@
|
||||||
border-right: 1px solid silver;
|
border-right: 1px solid silver;
|
||||||
}
|
}
|
||||||
.tab-receiver .tunings table {
|
.tab-receiver .tunings table {
|
||||||
|
width: 100%;
|
||||||
border-collapse: collapse;
|
border-collapse: collapse;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -27,45 +27,65 @@
|
||||||
<select class="hybrid_helper"
|
<select class="hybrid_helper"
|
||||||
name="rcmap_helper">
|
name="rcmap_helper">
|
||||||
<option value="AETR1234">Default</option>
|
<option value="AETR1234">Default</option>
|
||||||
<option value="AETR1234">Futaba / Hitec</option>
|
<option value="AETR1234">FrSky / Futaba / Hitec</option>
|
||||||
<option value="TAER1234">JR / Spektrum / Graupner</option>
|
<option value="TAER1234">Spektrum / Graupner / JR</option>
|
||||||
</select>
|
</select>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<div class="gui_box tunings grey" style="float: right;">
|
<div class="gui_box tunings grey" style="float: right;">
|
||||||
<table class="deadband" width="100%">
|
<table class="sticks">
|
||||||
<tr>
|
<tr>
|
||||||
<th i18n="receiverMidRc">
|
<th i18n="receiverStickMin"></th>
|
||||||
</th>
|
<th i18n="receiverStickCenter"></th>
|
||||||
<th i18n="receiverDeadband">
|
<th i18n="receiverStickMax"></th>
|
||||||
</th>
|
|
||||||
<th i18n="receiverYawDeadband">
|
|
||||||
</th>
|
|
||||||
</tr>
|
</tr>
|
||||||
<tr>
|
<tr>
|
||||||
<td>
|
<td>
|
||||||
<div class="numberspacer">
|
<div class="cf_tip" i18n_title="receiverHelpStickMin">
|
||||||
<input type="number" name="midrc" min="1200" max="1700" />
|
<input type="number" name="stick_min" min="1000" max="1200" />
|
||||||
<div class="helpicon cf_tip" i18n_title="receiverMidRcHelp"></div>
|
|
||||||
</div>
|
</div>
|
||||||
</td>
|
</td>
|
||||||
<td>
|
<td>
|
||||||
<div>
|
<div class="cf_tip" i18n_title="receiverHelpStickCenter">
|
||||||
|
<input type="number" name="stick_center" min="1401" max="1599" />
|
||||||
|
</div>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<div class="cf_tip" i18n_title="receiverHelpStickMax">
|
||||||
|
<input type="number" name="stick_max" min="1800" max="2000" />
|
||||||
|
</div>
|
||||||
|
</td>
|
||||||
|
</tr>
|
||||||
|
</table>
|
||||||
|
</div>
|
||||||
|
<div class="gui_box tunings grey" style="float: right;">
|
||||||
|
<table class="deadband">
|
||||||
|
<tr>
|
||||||
|
<th i18n="receiverDeadband"></th>
|
||||||
|
<th i18n="receiverYawDeadband"></th>
|
||||||
|
<th i18n="recevier3dDeadbandThrottle"></th>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>
|
||||||
|
<div class="cf_tip" i18n_title="receiverHelpDeadband">
|
||||||
<input type="number" name="deadband" step="1" min="0" max="32" />
|
<input type="number" name="deadband" step="1" min="0" max="32" />
|
||||||
<div class="helpicon cf_tip" i18n_title="receiverHelpDeadband"></div>
|
|
||||||
</div>
|
</div>
|
||||||
</td>
|
</td>
|
||||||
<td>
|
<td>
|
||||||
<div>
|
<div class="cf_tip" i18n_title="receiverHelpYawDeadband">
|
||||||
<input type="number" name="yaw_deadband" step="1" min="0" max="100" />
|
<input type="number" name="yaw_deadband" step="1" min="0" max="100" />
|
||||||
<div class="helpicon cf_tip" i18n_title="receiverHelpYawDeadband"></div>
|
</div>
|
||||||
|
</td>
|
||||||
|
<td>
|
||||||
|
<div class="cf_tip" i18n_title="receiverHelp3dDeadbandThrottle">
|
||||||
|
<input type="number" name="3ddeadbandthrottle" step="1" min="0" max="1000" />
|
||||||
</div>
|
</div>
|
||||||
</td>
|
</td>
|
||||||
</tr>
|
</tr>
|
||||||
</table>
|
</table>
|
||||||
</div>
|
</div>
|
||||||
<div class="gui_box grey tunings topspacer rcInterpolation">
|
<div class="gui_box grey tunings topspacer rcInterpolation">
|
||||||
<table class="rcInterpolation" width="100%">
|
<table class="rcInterpolation">
|
||||||
<tr>
|
<tr>
|
||||||
<th colspan="2" i18n="receiverRcInterpolation"></th>
|
<th colspan="2" i18n="receiverRcInterpolation"></th>
|
||||||
</tr>
|
</tr>
|
||||||
|
|
|
@ -15,24 +15,19 @@ TABS.receiver.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function get_rc_data() {
|
function get_rc_data() {
|
||||||
MSP.send_message(MSPCodes.MSP_RC, false, false, get_rc_tuning_data);
|
MSP.send_message(MSPCodes.MSP_RC, false, false, get_rssi_config);
|
||||||
}
|
}
|
||||||
|
|
||||||
function get_rc_tuning_data() {
|
function get_rssi_config() {
|
||||||
MSP.send_message(MSPCodes.MSP_RC_TUNING, false, false, get_bt_config_data);
|
MSP.send_message(MSPCodes.MSP_RSSI_CONFIG, false, false, get_rc_tuning);
|
||||||
}
|
}
|
||||||
|
|
||||||
function get_bt_config_data() {
|
function get_rc_tuning() {
|
||||||
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, get_rc_map);
|
MSP.send_message(MSPCodes.MSP_RC_TUNING, false, false, get_rc_map);
|
||||||
}
|
}
|
||||||
|
|
||||||
function get_rc_map() {
|
function get_rc_map() {
|
||||||
MSP.send_message(MSPCodes.MSP_RX_MAP, false, false, load_config);
|
MSP.send_message(MSPCodes.MSP_RX_MAP, false, false, load_rc_configs);
|
||||||
}
|
|
||||||
|
|
||||||
// Fetch features so we can check if RX_MSP is enabled:
|
|
||||||
function load_config() {
|
|
||||||
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, load_rc_configs);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_rc_configs() {
|
function load_rc_configs() {
|
||||||
|
@ -57,7 +52,7 @@ TABS.receiver.initialize = function (callback) {
|
||||||
$('#content').load("./tabs/receiver.html", process_html);
|
$('#content').load("./tabs/receiver.html", process_html);
|
||||||
}
|
}
|
||||||
|
|
||||||
MSP.send_message(MSPCodes.MSP_MISC, false, false, get_rc_data);
|
MSP.send_message(MSPCodes.MSP_FEATURE_CONFIG, false, false, get_rc_data);
|
||||||
|
|
||||||
function process_html() {
|
function process_html() {
|
||||||
// translate to user-selected language
|
// translate to user-selected language
|
||||||
|
@ -74,9 +69,9 @@ TABS.receiver.initialize = function (callback) {
|
||||||
if (semver.lt(CONFIG.apiVersion, "1.15.0")) {
|
if (semver.lt(CONFIG.apiVersion, "1.15.0")) {
|
||||||
$('.deadband').hide();
|
$('.deadband').hide();
|
||||||
} else {
|
} else {
|
||||||
$('.deadband input[name="midrc"]').val(RX_CONFIG.midrc);
|
$('.deadband input[name="yaw_deadband"]').val(RC_DEADBAND_CONFIG.yaw_deadband);
|
||||||
$('.deadband input[name="yaw_deadband"]').val(RC_deadband.yaw_deadband);
|
$('.deadband input[name="deadband"]').val(RC_DEADBAND_CONFIG.deadband);
|
||||||
$('.deadband input[name="deadband"]').val(RC_deadband.deadband);
|
$('.deadband input[name="3ddeadbandthrottle"]').val(RC_DEADBAND_CONFIG.deadband3d_throttle);
|
||||||
|
|
||||||
$('.deadband input[name="deadband"]').change(function () {
|
$('.deadband input[name="deadband"]').change(function () {
|
||||||
this.deadband = parseInt($(this).val());
|
this.deadband = parseInt($(this).val());
|
||||||
|
@ -84,7 +79,14 @@ TABS.receiver.initialize = function (callback) {
|
||||||
$('.deadband input[name="yaw_deadband"]').change(function () {
|
$('.deadband input[name="yaw_deadband"]').change(function () {
|
||||||
this.yawDeadband = parseInt($(this).val());
|
this.yawDeadband = parseInt($(this).val());
|
||||||
}).change();
|
}).change();
|
||||||
|
}
|
||||||
|
|
||||||
|
if (semver.lt(CONFIG.apiVersion, "1.15.0")) {
|
||||||
|
$('.sticks').hide();
|
||||||
|
} else {
|
||||||
|
$('.sticks input[name="stick_min"]').val(RX_CONFIG.stick_min);
|
||||||
|
$('.sticks input[name="stick_center"]').val(RX_CONFIG.stick_center);
|
||||||
|
$('.sticks input[name="stick_max"]').val(RX_CONFIG.stick_max);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||||
|
@ -226,7 +228,7 @@ TABS.receiver.initialize = function (callback) {
|
||||||
rssi_channel_e.append('<option value="' + i + '">' + i + '</option>');
|
rssi_channel_e.append('<option value="' + i + '">' + i + '</option>');
|
||||||
}
|
}
|
||||||
|
|
||||||
$('select[name="rssi_channel"]').val(MISC.rssi_channel);
|
$('select[name="rssi_channel"]').val(RSSI_CONFIG.channel);
|
||||||
|
|
||||||
var rateHeight = TABS.receiver.rateChartHeight;
|
var rateHeight = TABS.receiver.rateChartHeight;
|
||||||
|
|
||||||
|
@ -237,9 +239,12 @@ TABS.receiver.initialize = function (callback) {
|
||||||
|
|
||||||
$('a.update').click(function () {
|
$('a.update').click(function () {
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
|
||||||
RX_CONFIG.midrc = parseInt($('.deadband input[name="midrc"]').val());
|
RX_CONFIG.stick_max = parseInt($('.sticks input[name="stick_max"]').val());
|
||||||
RC_deadband.yaw_deadband = parseInt($('.deadband input[name="yaw_deadband"]').val());
|
RX_CONFIG.stick_center = parseInt($('.sticks input[name="stick_center"]').val());
|
||||||
RC_deadband.deadband = parseInt($('.deadband input[name="deadband"]').val());
|
RX_CONFIG.stick_min = parseInt($('.sticks input[name="stick_min"]').val());
|
||||||
|
RC_DEADBAND_CONFIG.yaw_deadband = parseInt($('.deadband input[name="yaw_deadband"]').val());
|
||||||
|
RC_DEADBAND_CONFIG.deadband = parseInt($('.deadband input[name="deadband"]').val());
|
||||||
|
RC_DEADBAND_CONFIG.deadband3d_throttle = ($('.deadband input[name="3ddeadbandthrottle"]').val());
|
||||||
}
|
}
|
||||||
|
|
||||||
// catch rc map
|
// catch rc map
|
||||||
|
@ -251,15 +256,16 @@ TABS.receiver.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// catch rssi aux
|
// catch rssi aux
|
||||||
MISC.rssi_channel = parseInt($('select[name="rssi_channel"]').val());
|
RSSI_CONFIG.channel = parseInt($('select[name="rssi_channel"]').val());
|
||||||
|
|
||||||
|
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.20.0")) {
|
||||||
RX_CONFIG.rcInterpolation = parseInt($('select[name="rcInterpolation-select"]').val());
|
RX_CONFIG.rcInterpolation = parseInt($('select[name="rcInterpolation-select"]').val());
|
||||||
RX_CONFIG.rcInterpolationInterval = parseInt($('input[name="rcInterpolationInterval-number"]').val());
|
RX_CONFIG.rcInterpolationInterval = parseInt($('input[name="rcInterpolationInterval-number"]').val());
|
||||||
}
|
}
|
||||||
|
|
||||||
function save_misc() {
|
function save_rssi_config() {
|
||||||
MSP.send_message(MSPCodes.MSP_SET_MISC, mspHelper.crunch(MSPCodes.MSP_SET_MISC), false, save_rc_configs);
|
MSP.send_message(MSPCodes.MSP_SET_RSSI_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_RSSI_CONFIG), false, save_rc_configs);
|
||||||
}
|
}
|
||||||
|
|
||||||
function save_rc_configs() {
|
function save_rc_configs() {
|
||||||
|
@ -286,7 +292,7 @@ TABS.receiver.initialize = function (callback) {
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
|
|
||||||
MSP.send_message(MSPCodes.MSP_SET_RX_MAP, mspHelper.crunch(MSPCodes.MSP_SET_RX_MAP), false, save_misc);
|
MSP.send_message(MSPCodes.MSP_SET_RX_MAP, mspHelper.crunch(MSPCodes.MSP_SET_RX_MAP), false, save_rssi_config);
|
||||||
});
|
});
|
||||||
|
|
||||||
$("a.sticks").click(function() {
|
$("a.sticks").click(function() {
|
||||||
|
@ -316,7 +322,7 @@ TABS.receiver.initialize = function (callback) {
|
||||||
});
|
});
|
||||||
|
|
||||||
// Only show the MSP control sticks if the MSP Rx feature is enabled
|
// Only show the MSP control sticks if the MSP Rx feature is enabled
|
||||||
$(".sticks_btn").toggle(BF_CONFIG.features.isEnabled('RX_MSP'));
|
$(".sticks_btn").toggle(FEATURE_CONFIG.features.isEnabled('RX_MSP'));
|
||||||
|
|
||||||
$('select[name="rx_refresh_rate"]').change(function () {
|
$('select[name="rx_refresh_rate"]').change(function () {
|
||||||
var plot_update_rate = parseInt($(this).val(), 10);
|
var plot_update_rate = parseInt($(this).val(), 10);
|
||||||
|
@ -448,7 +454,7 @@ TABS.receiver.initModelPreview = function () {
|
||||||
|
|
||||||
this.useSuperExpo = false;
|
this.useSuperExpo = false;
|
||||||
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
if (semver.gte(CONFIG.apiVersion, "1.16.0")) {
|
||||||
this.useSuperExpo = BF_CONFIG.features.isEnabled('SUPEREXPO_RATES');
|
this.useSuperExpo = FEATURE_CONFIG.features.isEnabled('SUPEREXPO_RATES');
|
||||||
}
|
}
|
||||||
|
|
||||||
var useOldRateCurve = false;
|
var useOldRateCurve = false;
|
||||||
|
|
|
@ -13,17 +13,7 @@ TABS.servos.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function get_servo_mix_rules() {
|
function get_servo_mix_rules() {
|
||||||
MSP.send_message(MSPCodes.MSP_SERVO_MIX_RULES, false, false, get_channel_forwarding);
|
MSP.send_message(MSPCodes.MSP_SERVO_MIX_RULES, false, false, get_rc_data);
|
||||||
}
|
|
||||||
|
|
||||||
function get_channel_forwarding() {
|
|
||||||
var nextFunction = get_rc_data;
|
|
||||||
|
|
||||||
if (semver.lt(CONFIG.apiVersion, "1.12.0")) {
|
|
||||||
MSP.send_message(MSPCodes.MSP_CHANNEL_FORWARDING, false, false, nextFunction);
|
|
||||||
} else {
|
|
||||||
nextFunction();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
function get_rc_data() {
|
function get_rc_data() {
|
||||||
|
|
|
@ -12,15 +12,11 @@ TABS.setup.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_status() {
|
function load_status() {
|
||||||
MSP.send_message(MSPCodes.MSP_STATUS, false, false, load_config);
|
MSP.send_message(MSPCodes.MSP_STATUS, false, false, load_mixer_config);
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_config() {
|
function load_mixer_config() {
|
||||||
MSP.send_message(MSPCodes.MSP_BF_CONFIG, false, false, load_misc_data);
|
MSP.send_message(MSPCodes.MSP_MIXER_CONFIG, false, false, load_html);
|
||||||
}
|
|
||||||
|
|
||||||
function load_misc_data() {
|
|
||||||
MSP.send_message(MSPCodes.MSP_MISC, false, false, load_html);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
function load_html() {
|
function load_html() {
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue