1
0
Fork 0
mirror of https://github.com/iNavFlight/inav-configurator.git synced 2025-07-14 03:49:53 +03:00

Merge remote-tracking branch 'origin/master' into osd-support

This commit is contained in:
Pawel Spychalski (DzikuVx) 2016-12-15 00:18:35 +01:00
commit 1bb6850c24
38 changed files with 899 additions and 628 deletions

View file

@ -622,10 +622,16 @@
"message": "Magnetometer Declination [deg]" "message": "Magnetometer Declination [deg]"
}, },
"configurationAutoDisarmDelay": { "configurationAutoDisarmDelay": {
"message": "Disarm motors after set delay(Seconds) (Requires MOTOR_STOP feature)" "message": "Disarm delay [Seconds]"
},
"configurationAutoDisarmDelayHelp": {
"message": "Requires MOTOR_STOP feature"
}, },
"configurationDisarmKillSwitch": { "configurationDisarmKillSwitch": {
"message": "Disarm motors regardless of throttle value (When arming via AUX channel)" "message": "Disarm regardless of throttle value"
},
"configurationDisarmKillSwitchHelp": {
"message": "When arming via AUX channel"
}, },
"configurationThrottleMinimum": { "configurationThrottleMinimum": {
"message": "Minimum Throttle" "message": "Minimum Throttle"
@ -693,9 +699,6 @@
"configurationCalculatedCyclesSec": { "configurationCalculatedCyclesSec": {
"message": "Cycles/Sec (Hz)" "message": "Cycles/Sec (Hz)"
}, },
"configurationLoopTimeHelp": {
"message": "<strong>Note:</strong> Changing this may require PID re-tuning."
},
"configurationGPS": { "configurationGPS": {
"message": "GPS" "message": "GPS"
}, },
@ -1811,6 +1814,36 @@
"pidTuningTPABreakPointHelp": { "pidTuningTPABreakPointHelp": {
"message": "Throttle PID Attenuation begins when Throttle position exceeds this value. " "message": "Throttle PID Attenuation begins when Throttle position exceeds this value. "
}, },
"configurationAsyncMode": {
"message": "Asynchronous mode"
},
"configurationGyroFrequencyTitle": {
"message": "Gyroscope task frequency"
},
"configurationAccelerometerFrequencyTitle": {
"message": "Accelerometer task frequency"
},
"configurationAttitudeFrequencyTitle": {
"message": "Attitude task frequency"
},
"configurationGyroLpfHelp": {
"message": "Hardware based cutoff frequency for gyroscope. In general, bigger value is better but makes UAV more sensitive to vibrations"
},
"configurationAsyncModeHelp": {
"message": "See Firmware \"Looptime\" documentation for details"
},
"configurationGyroFrequencyHelp": {
"message": "In general, higher value is better but makes UAV more sensitive to vibrations. Should be kept above 'Flight Controller Loop Time' frequency. Maximal practical value is hardware dependant. If set too high, board might not run properly. Observe CPU usage."
},
"configurationAccelerometerFrequencyHelp": {
"message": "For Acro purposes, this value can be lowered from default"
},
"configurationAttitudeFrequencyHelp": {
"message": "For Acro purposes, this value can be lowered from default"
},
"configurationLoopTimeHelp": {
"message": "In general, higher value is better. With asynchronous gyroscope, should be kept below gyro update frequency. Maximal practical value is hardware dependant. If set too high, board might not run properly. Observe CPU usage."
},
"tabOSD": { "tabOSD": {
"message": "OSD" "message": "OSD"
} }

Binary file not shown.

After

Width:  |  Height:  |  Size: 16 KiB

Binary file not shown.

Binary file not shown.

After

Width:  |  Height:  |  Size: 20 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 21 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 20 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 16 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 20 KiB

Binary file not shown.

Binary file not shown.

After

Width:  |  Height:  |  Size: 17 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 16 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 17 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 17 KiB

506
js/fc.js
View file

@ -41,43 +41,52 @@ var ADVANCED_CONFIG;
var INAV_PID_CONFIG; var INAV_PID_CONFIG;
var PID_ADVANCED; var PID_ADVANCED;
var FILTER_CONFIG; var FILTER_CONFIG;
var SENSOR_STATUS;
var FC = { var FC = {
isRatesInDps: function () { isRatesInDps: function () {
if (typeof CONFIG != "undefined" && CONFIG.flightControllerIdentifier == "INAV" && semver.gt(CONFIG.flightControllerVersion, "1.1.0")) { return !!(typeof CONFIG != "undefined" && CONFIG.flightControllerIdentifier == "INAV" && semver.gt(CONFIG.flightControllerVersion, "1.1.0"));
return true;
} else {
return false;
}
}, },
resetState: function() { resetState: function() {
SENSOR_STATUS = {
isHardwareHealthy: 0,
gyroHwStatus: 0,
accHwStatus: 0,
magHwStatus: 0,
baroHwStatus: 0,
gpsHwStatus: 0,
rangeHwStatus: 0,
speedHwStatus: 0,
flowHwStatus: 0
};
CONFIG = { CONFIG = {
apiVersion: "0.0.0", apiVersion: "0.0.0",
flightControllerIdentifier: '', flightControllerIdentifier: '',
flightControllerVersion: '', flightControllerVersion: '',
version: 0, version: 0,
buildInfo: '', buildInfo: '',
multiType: 0, multiType: 0,
msp_version: 0, // not specified using semantic versioning msp_version: 0, // not specified using semantic versioning
capability: 0, capability: 0,
cycleTime: 0, cycleTime: 0,
i2cError: 0, i2cError: 0,
activeSensors: 0, activeSensors: 0,
mode: 0, mode: 0,
profile: 0, profile: 0,
uid: [0, 0, 0], uid: [0, 0, 0],
accelerometerTrims: [0, 0] accelerometerTrims: [0, 0]
}; };
BF_CONFIG = { BF_CONFIG = {
mixerConfiguration: 0, mixerConfiguration: 0,
features: 0, features: 0,
serialrx_type: 0, serialrx_type: 0,
board_align_roll: 0, board_align_roll: 0,
board_align_pitch: 0, board_align_pitch: 0,
board_align_yaw: 0, board_align_yaw: 0,
currentscale: 0, currentscale: 0,
currentoffset: 0 currentoffset: 0
}; };
LED_STRIP = []; LED_STRIP = [];
@ -103,17 +112,17 @@ var FC = {
}; };
RC_tuning = { RC_tuning = {
RC_RATE: 0, RC_RATE: 0,
RC_EXPO: 0, RC_EXPO: 0,
roll_pitch_rate: 0, // pre 1.7 api only roll_pitch_rate: 0, // pre 1.7 api only
roll_rate: 0, roll_rate: 0,
pitch_rate: 0, pitch_rate: 0,
yaw_rate: 0, yaw_rate: 0,
dynamic_THR_PID: 0, dynamic_THR_PID: 0,
throttle_MID: 0, throttle_MID: 0,
throttle_EXPO: 0, throttle_EXPO: 0,
dynamic_THR_breakpoint: 0, dynamic_THR_breakpoint: 0,
RC_YAW_EXPO: 0 RC_YAW_EXPO: 0
}; };
AUX_CONFIG = []; AUX_CONFIG = [];
@ -132,52 +141,52 @@ var FC = {
mspBaudRate: 0, mspBaudRate: 0,
gpsBaudRate: 0, gpsBaudRate: 0,
gpsPassthroughBaudRate: 0, gpsPassthroughBaudRate: 0,
cliBaudRate: 0, cliBaudRate: 0
}; };
SENSOR_DATA = { SENSOR_DATA = {
gyroscope: [0, 0, 0], gyroscope: [0, 0, 0],
accelerometer: [0, 0, 0], accelerometer: [0, 0, 0],
magnetometer: [0, 0, 0], magnetometer: [0, 0, 0],
altitude: 0, altitude: 0,
sonar: 0, sonar: 0,
kinematics: [0.0, 0.0, 0.0], kinematics: [0.0, 0.0, 0.0],
debug: [0, 0, 0, 0] debug: [0, 0, 0, 0]
}; };
MOTOR_DATA = new Array(8); MOTOR_DATA = new Array(8);
SERVO_DATA = new Array(8); SERVO_DATA = new Array(8);
GPS_DATA = { GPS_DATA = {
fix: 0, fix: 0,
numSat: 0, numSat: 0,
lat: 0, lat: 0,
lon: 0, lon: 0,
alt: 0, alt: 0,
speed: 0, speed: 0,
ground_course: 0, ground_course: 0,
distanceToHome: 0, distanceToHome: 0,
ditectionToHome: 0, ditectionToHome: 0,
update: 0, update: 0,
hdop: 0, hdop: 0,
eph: 0, eph: 0,
epv: 0, epv: 0,
messageDt: 0, messageDt: 0,
errors: 0, errors: 0,
timeouts: 0, timeouts: 0,
packetCount: 0 packetCount: 0
}; };
ANALOG = { ANALOG = {
voltage: 0, voltage: 0,
mAhdrawn: 0, mAhdrawn: 0,
rssi: 0, rssi: 0,
amperage: 0 amperage: 0
}; };
ARMING_CONFIG = { ARMING_CONFIG = {
auto_disarm_delay: 0, auto_disarm_delay: 0,
disarm_kill_switch: 0 disarm_kill_switch: 0
}; };
FC_CONFIG = { FC_CONFIG = {
@ -185,21 +194,21 @@ var FC = {
}; };
MISC = { MISC = {
midrc: 0, midrc: 0,
minthrottle: 0, minthrottle: 0,
maxthrottle: 0, maxthrottle: 0,
mincommand: 0, mincommand: 0,
failsafe_throttle: 0, failsafe_throttle: 0,
gps_type: 0, gps_type: 0,
gps_baudrate: 0, gps_baudrate: 0,
gps_ubx_sbas: 0, gps_ubx_sbas: 0,
multiwiicurrentoutput: 0, multiwiicurrentoutput: 0,
rssi_channel: 0, rssi_channel: 0,
placeholder2: 0, placeholder2: 0,
mag_declination: 0, // not checked mag_declination: 0, // not checked
vbatscale: 0, vbatscale: 0,
vbatmincellvoltage: 0, vbatmincellvoltage: 0,
vbatmaxcellvoltage: 0, vbatmaxcellvoltage: 0,
vbatwarningcellvoltage: 0 vbatwarningcellvoltage: 0
}; };
@ -217,7 +226,7 @@ var FC = {
gyroSoftLpfHz: null, gyroSoftLpfHz: null,
dtermLpfHz: null, dtermLpfHz: null,
yawLpfHz: null yawLpfHz: null
} };
PID_ADVANCED = { PID_ADVANCED = {
rollPitchItermIgnoreRate: null, rollPitchItermIgnoreRate: null,
@ -225,7 +234,7 @@ var FC = {
yawPLimit: null, yawPLimit: null,
axisAccelerationLimitRollPitch: null, axisAccelerationLimitRollPitch: null,
axisAccelerationLimitYaw: null axisAccelerationLimitYaw: null
} };
INAV_PID_CONFIG = { INAV_PID_CONFIG = {
asynchronousMode: null, asynchronousMode: null,
@ -236,13 +245,13 @@ var FC = {
yawJumpPreventionLimit: null, yawJumpPreventionLimit: null,
gyroscopeLpf: null, gyroscopeLpf: null,
accSoftLpfHz: null accSoftLpfHz: null
} };
_3D = { _3D = {
deadband3d_low: 0, deadband3d_low: 0,
deadband3d_high: 0, deadband3d_high: 0,
neutral3d: 0, neutral3d: 0,
deadband3d_throttle: 0 deadband3d_throttle: 0
}; };
DATAFLASH = { DATAFLASH = {
@ -258,7 +267,7 @@ var FC = {
state: 0, state: 0,
filesystemLastError: 0, filesystemLastError: 0,
freeSizeKB: 0, freeSizeKB: 0,
totalSizeKB: 0, totalSizeKB: 0
}; };
BLACKBOX = { BLACKBOX = {
@ -274,36 +283,36 @@ var FC = {
}; };
RC_deadband = { RC_deadband = {
deadband: 0, deadband: 0,
yaw_deadband: 0, yaw_deadband: 0,
alt_hold_deadband: 0 alt_hold_deadband: 0
}; };
SENSOR_ALIGNMENT = { SENSOR_ALIGNMENT = {
align_gyro: 0, align_gyro: 0,
align_acc: 0, align_acc: 0,
align_mag: 0 align_mag: 0
}; };
RX_CONFIG = { RX_CONFIG = {
serialrx_provider: 0, serialrx_provider: 0,
maxcheck: 0, maxcheck: 0,
midrc: 0, midrc: 0,
mincheck: 0, mincheck: 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,
nrf24rx_protocol: 0, nrf24rx_protocol: 0,
nrf24rx_id: 0 nrf24rx_id: 0
}; };
FAILSAFE_CONFIG = { FAILSAFE_CONFIG = {
failsafe_delay: 0, failsafe_delay: 0,
failsafe_off_delay: 0, failsafe_off_delay: 0,
failsafe_throttle: 0, failsafe_throttle: 0,
failsafe_kill_switch: 0, failsafe_kill_switch: 0,
failsafe_throttle_low_delay: 0, failsafe_throttle_low_delay: 0,
failsafe_procedure: 0 failsafe_procedure: 0
}; };
RXFAIL_CONFIG = []; RXFAIL_CONFIG = [];
@ -371,7 +380,7 @@ var FC = {
} }
return features; return features;
}, },
isFeatureEnabled: function(featureName, features) { isFeatureEnabled: function (featureName, features) {
for (var i = 0; i < features.length; i++) { for (var i = 0; i < features.length; i++) {
if (features[i].name == featureName && bit_check(BF_CONFIG.features, features[i].bit)) { if (features[i].name == featureName && bit_check(BF_CONFIG.features, features[i].bit)) {
return true; return true;
@ -384,56 +393,237 @@ var FC = {
}, },
getLooptimes: function () { getLooptimes: function () {
return { return {
125: { 125: {
defaultLooptime: 2000, defaultLooptime: 2000,
looptimes: { looptimes: {
4000: "250Hz", 4000: "250Hz",
3000: "334Hz", 3000: "334Hz",
2000: "500Hz", 2000: "500Hz",
1500: "667Hz", 1500: "667Hz",
1000: "1kHz", 1000: "1kHz",
500: "2kHz", 500: "2kHz",
250: "4kHz", 250: "4kHz",
125: "8kHz" 125: "8kHz"
} }
}, },
1000: { 1000: {
defaultLooptime: 2000, defaultLooptime: 2000,
looptimes: { looptimes: {
4000: "250Hz", 4000: "250Hz",
2000: "500Hz", 2000: "500Hz",
1000: "1kHz" 1000: "1kHz"
} }
} }
}; };
}, },
getGyroLpfValues: function () { getGyroFrequencies: function () {
return [ return {
{ 125: {
tick: 125, defaultLooptime: 1000,
defaultDenominator: 16, looptimes: {
label: "256Hz" 4000: "250Hz",
}, { 3000: "334Hz",
tick: 1000, 2000: "500Hz",
defaultDenominator: 2, 1500: "667Hz",
label: "188Hz" 1000: "1kHz",
}, { 500: "2kHz",
tick: 1000, 250: "4kHz",
defaultDenominator: 2, 125: "8kHz"
label: "98Hz" }
}, { },
tick: 1000, 1000: {
defaultDenominator: 2, defaultLooptime: 1000,
label: "42Hz" looptimes: {
}, { 4000: "250Hz",
tick: 1000, 2000: "500Hz",
defaultDenominator: 2, 1000: "1kHz"
label: "20Hz" }
}, { }
tick: 1000, };
defaultDenominator: 2, },
label: "10Hz" getGyroLpfValues: function () {
} return [
]; {
} tick: 125,
defaultDenominator: 16,
label: "256Hz"
},
{
tick: 1000,
defaultDenominator: 2,
label: "188Hz"
},
{
tick: 1000,
defaultDenominator: 2,
label: "98Hz"
},
{
tick: 1000,
defaultDenominator: 2,
label: "42Hz"
},
{
tick: 1000,
defaultDenominator: 2,
label: "20Hz"
},
{
tick: 1000,
defaultDenominator: 2,
label: "10Hz"
}
];
},
getGpsProtocols: function () {
return [
'NMEA',
'UBLOX',
'I2C-NAV',
'DJI NAZA'
]
},
getGpsBaudRates: function () {
return [
'115200',
'57600',
'38400',
'19200',
'9600'
];
},
getGpsSbasProviders: function () {
return [
'Autodetect',
'European EGNOS',
'North American WAAS',
'Japanese MSAS',
'Indian GAGAN',
'Disabled'
];
},
getSerialRxTypes: function () {
return [
'SPEKTRUM1024',
'SPEKTRUM2048',
'SBUS',
'SUMD',
'SUMH',
'XBUS_MODE_B',
'XBUS_MODE_B_RJ01',
'IBUS'
];
},
getNrf24ProtocolTypes: function () {
return [
'V202 250Kbps',
'V202 1Mbps',
'Syma X',
'Syma X5C',
'Cheerson CX10',
'Cheerson CX10A',
'JJRC H8_3D',
'iNav Reference protocol'
];
},
getSensorAlignments: function () {
return [
'CW 0°',
'CW 90°',
'CW 180°',
'CW 270°',
'CW 0° flip',
'CW 90° flip',
'CW 180° flip',
'CW 270° flip'
];
},
getEscProtocols: function () {
return {
0: {
name: "STANDARD",
defaultRate: 400,
rates: {
50: "50Hz",
400: "400Hz"
}
},
1: {
name: "ONESHOT125",
defaultRate: 1000,
rates: {
400: "400Hz",
1000: "1kHz",
2000: "2kHz"
}
},
2: {
name: "ONESHOT42",
defaultRate: 2000,
rates: {
400: "400Hz",
1000: "1kHz",
2000: "2kHz",
4000: "4kHz",
8000: "8kHz"
}
},
3: {
name: "MULTISHOT",
defaultRate: 2000,
rates: {
400: "400Hz",
1000: "1kHz",
2000: "2kHz",
4000: "4kHz",
8000: "8kHz"
}
},
4: {
name: "BRUSHED",
defaultRate: 8000,
rates: {
8000: "8kHz",
16000: "16kHz",
32000: "32kHz"
}
}
};
},
getServoRates: function () {
return {
50: "50Hz",
60: "60Hz",
100: "100Hz",
200: "200Hz",
400: "400Hz"
};
},
getAsyncModes: function () {
return [
'Disabled',
'Gyro',
'All'
]
},
getAccelerometerTaskFrequencies: function () {
return {
100: '100Hz',
200: '200Hz',
250: '250Hz',
500: '500Hz',
750: '750Hz',
1000: '1kHz'
}
},
getAttitudeTaskFrequencies: function () {
return {
100: '100Hz',
200: '200Hz',
250: '250Hz',
500: '500Hz',
750: '750Hz',
1000: '1kHz'
}
}
}; };

View file

@ -9,28 +9,42 @@ function localize() {
return chrome.i18n.getMessage(messageID); return chrome.i18n.getMessage(messageID);
}; };
$('[i18n]:not(.i18n-replaced').each(function() { $('[i18n]:not(.i18n-replaced)').each(function() {
var element = $(this); var element = $(this);
element.html(translate(element.attr('i18n'))); element.html(translate(element.attr('i18n')));
element.addClass('i18n-replaced'); element.addClass('i18n-replaced');
}); });
$('[i18n_title]:not(.i18n_title-replaced').each(function() { $('[data-i18n]:not(.i18n-replaced)').each(function() {
var element = $(this);
element.html(translate(element.data('i18n')));
element.addClass('i18n-replaced');
});
$('[i18n_title]:not(.i18n_title-replaced)').each(function() {
var element = $(this); var element = $(this);
element.attr('title', translate(element.attr('i18n_title'))); element.attr('title', translate(element.attr('i18n_title')));
element.addClass('i18n_title-replaced'); element.addClass('i18n_title-replaced');
}); });
$('[i18n_value]:not(.i18n_value-replaced').each(function() { $('[data-i18n_title]:not(.i18n_title-replaced)').each(function() {
var element = $(this);
element.attr('title', translate(element.data('i18n_title')));
element.addClass('i18n_title-replaced');
});
$('[i18n_value]:not(.i18n_value-replaced)').each(function() {
var element = $(this); var element = $(this);
element.val(translate(element.attr('i18n_value'))); element.val(translate(element.attr('i18n_value')));
element.addClass('i18n_value-replaced'); element.addClass('i18n_value-replaced');
}); });
$('[i18n_placeholder]:not(.i18n_placeholder-replaced').each(function() { $('[i18n_placeholder]:not(.i18n_placeholder-replaced)').each(function() {
var element = $(this); var element = $(this);
element.attr('placeholder', translate(element.attr('i18n_placeholder'))); element.attr('placeholder', translate(element.attr('i18n_placeholder')));

View file

@ -82,6 +82,7 @@ var MSPCodes = {
MSP_SENSOR_ALIGNMENT: 126, MSP_SENSOR_ALIGNMENT: 126,
MSP_LED_STRIP_MODECOLOR:127, MSP_LED_STRIP_MODECOLOR:127,
MSP_STATUS_EX: 150, MSP_STATUS_EX: 150,
MSP_SENSOR_STATUS: 151,
MSP_SET_RAW_RC: 200, MSP_SET_RAW_RC: 200,
MSP_SET_RAW_GPS: 201, MSP_SET_RAW_GPS: 201,

View file

@ -69,6 +69,19 @@ var mspHelper = (function (gui) {
gui.updateStatusBar(); gui.updateStatusBar();
break; break;
case MSPCodes.MSP_SENSOR_STATUS:
SENSOR_STATUS.isHardwareHealthy = data.getUint8(0);
SENSOR_STATUS.gyroHwStatus = data.getUint8(1);
SENSOR_STATUS.accHwStatus = data.getUint8(2);
SENSOR_STATUS.magHwStatus = data.getUint8(3);
SENSOR_STATUS.baroHwStatus = data.getUint8(4);
SENSOR_STATUS.gpsHwStatus = data.getUint8(5);
SENSOR_STATUS.rangeHwStatus = data.getUint8(6);
SENSOR_STATUS.speedHwStatus = data.getUint8(7);
SENSOR_STATUS.flowHwStatus = data.getUint8(8);
sensor_status_ex(SENSOR_STATUS);
break;
case MSPCodes.MSP_RAW_IMU: case MSPCodes.MSP_RAW_IMU:
// 512 for mpu6050, 256 for mma // 512 for mpu6050, 256 for mma
// currently we are unable to differentiate between the sensor types, so we are goign with 512 // currently we are unable to differentiate between the sensor types, so we are goign with 512

View file

@ -308,79 +308,72 @@ function read_serial(info) {
} }
} }
//FIXME move it into GUI function sensor_status_ex(hw_status)
function sensor_status(sensors_detected) { {
// initialize variable (if it wasn't) var statusHash = sensor_status_hash(hw_status);
if (!sensor_status.previous_sensors_detected) {
sensor_status.previous_sensors_detected = -1; // Otherwise first iteration will not be run if sensors_detected == 0
}
// update UI (if necessary) if (sensor_status_ex.previousHash == statusHash) {
if (sensor_status.previous_sensors_detected == sensors_detected) {
return; return;
} }
// set current value sensor_status_ex.previousHash = statusHash;
sensor_status.previous_sensors_detected = sensors_detected;
sensor_status_update_icon('.gyro', '.gyroicon', hw_status.gyroHwStatus);
sensor_status_update_icon('.accel', '.accicon', hw_status.accHwStatus);
sensor_status_update_icon('.mag', '.magicon', hw_status.magHwStatus);
sensor_status_update_icon('.baro', '.baroicon', hw_status.baroHwStatus);
sensor_status_update_icon('.gps', '.gpsicon', hw_status.gpsHwStatus);
sensor_status_update_icon('.sonar', '.sonaricon', hw_status.rangeHwStatus);
sensor_status_update_icon('.airspeed', '.airspeedicon', hw_status.speedHwStatus);
sensor_status_update_icon('.opflow', '.opflowicon', hw_status.flowHwStatus);
}
function sensor_status_update_icon(sensId, sensIconId, status)
{
var e_sensor_status = $('#sensor-status'); var e_sensor_status = $('#sensor-status');
if (have_sensor(sensors_detected, 'acc')) { if (status == 0) {
$('.accel', e_sensor_status).addClass('on'); $(sensId, e_sensor_status).removeClass('on');
$('.accicon', e_sensor_status).addClass('active'); $(sensIconId, e_sensor_status).removeClass('active');
$(sensIconId, e_sensor_status).removeClass('error');
} else {
$('.accel', e_sensor_status).removeClass('on');
$('.accicon', e_sensor_status).removeClass('active');
} }
else if (status == 1) {
if (have_sensor(sensors_detected, 'gyro')) { $(sensId, e_sensor_status).addClass('on');
$('.gyro', e_sensor_status).addClass('on'); $(sensIconId, e_sensor_status).addClass('active');
$('.gyroicon', e_sensor_status).addClass('active'); $(sensIconId, e_sensor_status).removeClass('error');
} else {
$('.gyro', e_sensor_status).removeClass('on');
$('.gyroicon', e_sensor_status).removeClass('active');
} }
else {
if (have_sensor(sensors_detected, 'baro')) { $(sensId, e_sensor_status).removeClass('on');
$('.baro', e_sensor_status).addClass('on'); $(sensIconId, e_sensor_status).removeClass('active');
$('.baroicon', e_sensor_status).addClass('active'); $(sensIconId, e_sensor_status).addClass('error');
} else {
$('.baro', e_sensor_status).removeClass('on');
$('.baroicon', e_sensor_status).removeClass('active');
} }
}
if (have_sensor(sensors_detected, 'mag')) { function sensor_status_hash(hw_status)
$('.mag', e_sensor_status).addClass('on'); {
$('.magicon', e_sensor_status).addClass('active'); return "S" +
} else { hw_status.isHardwareHealthy +
$('.mag', e_sensor_status).removeClass('on'); hw_status.gyroHwStatus +
$('.magicon', e_sensor_status).removeClass('active'); hw_status.accHwStatus +
} hw_status.magHwStatus +
hw_status.baroHwStatus +
hw_status.gpsHwStatus +
hw_status.rangeHwStatus +
hw_status.speedHwStatus +
hw_status.flowHwStatus;
}
if (have_sensor(sensors_detected, 'gps')) { function sensor_status(sensors_detected) {
$('.gps', e_sensor_status).addClass('on'); SENSOR_STATUS.isHardwareHealthy = 1;
$('.gpsicon', e_sensor_status).addClass('active'); SENSOR_STATUS.gyroHwStatus = have_sensor(sensors_detected, 'gyro') ? 1 : 0;
} else { SENSOR_STATUS.accHwStatus = have_sensor(sensors_detected, 'acc') ? 1 : 0;
$('.gps', e_sensor_status).removeClass('on'); SENSOR_STATUS.magHwStatus = have_sensor(sensors_detected, 'mag') ? 1 : 0;
$('.gpsicon', e_sensor_status).removeClass('active'); SENSOR_STATUS.baroHwStatus = have_sensor(sensors_detected, 'baro') ? 1 : 0;
} SENSOR_STATUS.gpsHwStatus = have_sensor(sensors_detected, 'gps') ? 1 : 0;
SENSOR_STATUS.rangeHwStatus = have_sensor(sensors_detected, 'sonar') ? 1 : 0;
if (have_sensor(sensors_detected, 'sonar')) { SENSOR_STATUS.speedHwStatus = have_sensor(sensors_detected, 'airspeed') ? 1 : 0;
$('.sonar', e_sensor_status).addClass('on'); SENSOR_STATUS.flowHwStatus = have_sensor(sensors_detected, 'opflow') ? 1 : 0;
$('.sonaricon', e_sensor_status).addClass('active'); sensor_status_ex(SENSOR_STATUS);
} else {
$('.sonar', e_sensor_status).removeClass('on');
$('.sonaricon', e_sensor_status).removeClass('active');
}
if (have_sensor(sensors_detected, 'opflow')) {
$('.opflow', e_sensor_status).addClass('on');
$('.opflowicon', e_sensor_status).addClass('active');
} else {
$('.opflow', e_sensor_status).removeClass('on');
$('.opflowicon', e_sensor_status).removeClass('active');
}
} }
function have_sensor(sensors_detected, sensor_code) { function have_sensor(sensors_detected, sensor_code) {
@ -398,6 +391,8 @@ function have_sensor(sensors_detected, sensor_code) {
return bit_check(sensors_detected, 4); return bit_check(sensors_detected, 4);
case 'opflow': case 'opflow':
return bit_check(sensors_detected, 5); return bit_check(sensors_detected, 5);
case 'airspeed':
return bit_check(sensors_detected, 6);
} }
return false; return false;
} }

View file

@ -243,7 +243,6 @@ input[type="number"]::-webkit-inner-spin-button {
.gyroicon.active { .gyroicon.active {
background-image: url(images/icons/sensor_gyro_on.png); background-image: url(images/icons/sensor_gyro_on.png);
color: #61d514;
color: #818181; color: #818181;
} }
@ -262,10 +261,14 @@ input[type="number"]::-webkit-inner-spin-button {
.accicon.active { .accicon.active {
background-image: url(images/icons/sensor_acc_on.png); background-image: url(images/icons/sensor_acc_on.png);
color: #61d514;
color: #818181; color: #818181;
} }
.accicon.error {
background-image: url(images/icons/sensor_acc_error.png);
color: #d40000;
}
.magicon { .magicon {
background-image: url(images/icons/sensor_mag_off.png); background-image: url(images/icons/sensor_mag_off.png);
background-size: 42px; background-size: 42px;
@ -283,6 +286,10 @@ input[type="number"]::-webkit-inner-spin-button {
background-image: url(images/icons/sensor_mag_on.png); background-image: url(images/icons/sensor_mag_on.png);
color: #818181; color: #818181;
} }
.magicon.error {
background-image: url(images/icons/sensor_mag_error.png);
color: #d40000;
}
.gpsicon { .gpsicon {
background-image: url(images/icons/sensor_sat_off.png); background-image: url(images/icons/sensor_sat_off.png);
@ -302,6 +309,11 @@ input[type="number"]::-webkit-inner-spin-button {
color: #818181; color: #818181;
} }
.gpsicon.error {
background-image: url(images/icons/sensor_sat_error.png);
color: #d40000;
}
.opflowicon { .opflowicon {
background-image: url(images/icons/sensor_flow_off.png); background-image: url(images/icons/sensor_flow_off.png);
background-size: 42px; background-size: 42px;
@ -320,6 +332,11 @@ input[type="number"]::-webkit-inner-spin-button {
color: #818181; color: #818181;
} }
.opflowicon.error {
background-image: url(images/icons/sensor_flow_error.png);
color: #d40000;
}
.baroicon { .baroicon {
background-image: url(images/icons/sensor_baro_off.png); background-image: url(images/icons/sensor_baro_off.png);
background-size: 40px; background-size: 40px;
@ -338,6 +355,11 @@ input[type="number"]::-webkit-inner-spin-button {
color: #818181; color: #818181;
} }
.baroicon.error {
background-image: url(images/icons/sensor_baro_error.png);
color: #d40000;
}
.sonaricon { .sonaricon {
background-image: url(images/icons/sensor_sonar_off.png); background-image: url(images/icons/sensor_sonar_off.png);
background-size: 41px; background-size: 41px;
@ -356,6 +378,34 @@ input[type="number"]::-webkit-inner-spin-button {
color: #818181; color: #818181;
} }
.sonaricon.error {
background-image: url(images/icons/sensor_sonar_error.png);
color: #d40000;
}
.airspeedicon {
background-image: url(images/icons/sensor_airspeed_off.png);
background-size: 41px;
background-position: -4px 1px;
background-repeat: no-repeat;
height: 30px;
margin-top: 3px;
width: 100%;
padding-top: 40px;
color: #4f4f4f;
text-align: center;
}
.airspeedicon.active {
background-image: url(images/icons/sensor_airspeed_on.png);
color: #818181;
}
.airspeedicon.error {
background-image: url(images/icons/sensor_airspeed_error.png);
color: #d40000;
}
#sensor-status li:last-child { #sensor-status li:last-child {
border-right: 0px solid #c0c0c0; border-right: 0px solid #c0c0c0;
border-top-right-radius: 5px; border-top-right-radius: 5px;

View file

@ -181,6 +181,9 @@
<li class="sonar" title="Sonar / Range finder"> <li class="sonar" title="Sonar / Range finder">
<div class="sonaricon">Sonar</div> <div class="sonaricon">Sonar</div>
</li> </li>
<li class="airspeed" title="Airspeed">
<div class="airspeedicon">Speed</div>
</li>
</ul> </ul>
</div> </div>
<div id="quad-status_wrapper"> <div id="quad-status_wrapper">

View file

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

View file

@ -280,6 +280,10 @@ TABS.adjustments.initialize = function (callback) {
// status data pulled via separate timer with static speed // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function () { GUI.interval_add('status_pull', function () {
MSP.send_message(MSPCodes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
MSP.send_message(MSPCodes.MSP_SENSOR_STATUS);
}
}, 250, true); }, 250, true);
GUI.content_ready(callback); GUI.content_ready(callback);

View file

@ -293,6 +293,10 @@ TABS.auxiliary.initialize = function (callback) {
// status data pulled via separate timer with static speed // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function () { GUI.interval_add('status_pull', function () {
MSP.send_message(MSPCodes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
MSP.send_message(MSPCodes.MSP_SENSOR_STATUS);
}
}, 250, true); }, 250, true);
GUI.content_ready(callback); GUI.content_ready(callback);

View file

@ -25,7 +25,7 @@
} }
.tab-configuration table td { .tab-configuration table td {
padding: 5px 3px; padding: 5px 0;
} }
.tab-configuration table thead tr:first-child { .tab-configuration table thead tr:first-child {
@ -203,6 +203,7 @@
.tab-configuration .number, .tab-configuration .number,
.tab-configuration .select, .tab-configuration .select,
.tab-configuration .checkbox,
hr hr
{ {
margin-bottom: 5px; margin-bottom: 5px;
@ -214,7 +215,8 @@ hr
} }
.tab-configuration .number:last-child, .tab-configuration .number:last-child,
.tab-configuration .select:last-child { .tab-configuration .select:last-child,
.tab-configuration .checkbox:last-child{
border-bottom: none; border-bottom: none;
padding-bottom: 0; padding-bottom: 0;
margin-bottom: 0; margin-bottom: 0;
@ -492,6 +494,9 @@ hr
#esc-protocols .select, #esc-protocols .select,
#servo-rate-container .select, #servo-rate-container .select,
.motorstop .select,
.motorstop .checkbox,
.motorstop .number,
.system .select, .system .select,
.system .checkbox, .system .checkbox,
.system .number { .system .number {
@ -500,7 +505,13 @@ hr
#esc-protocols label, #esc-protocols label,
#servo-rate-container label, #servo-rate-container label,
.motorstop label,
.system label { .system label {
position: absolute; position: absolute;
left: 10em; left: 10em;
} }
.esc-priority label,
.features.esc label{
position: inherit;
}

View file

@ -1,18 +1,18 @@
<div class="tab-configuration toolbar_fixed_bottom"> <div class="tab-configuration toolbar_fixed_bottom">
<div class="content_wrapper"> <div class="content_wrapper">
<div class="tab_title" i18n="tabConfiguration">Configuration</div> <div class="tab_title" data-i18n="tabConfiguration">Configuration</div>
<div class="cf_doc_version_bt"> <div class="cf_doc_version_bt">
<a id="button-documentation" href="https://github.com/iNavFlight/inav/releases" target="_blank"></a> <a id="button-documentation" href="https://github.com/iNavFlight/inav/releases" target="_blank"></a>
</div> </div>
<div class="note" style="margin-bottom: 20px;"> <div class="note" style="margin-bottom: 20px;">
<div class="note_spacer"> <div class="note_spacer">
<p i18n="configurationFeaturesHelp"></p> <p data-i18n="configurationFeaturesHelp"></p>
</div> </div>
</div> </div>
<div class="leftWrapper mixer"> <div class="leftWrapper mixer">
<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="configurationMixer"></div> <div class="spacer_box_title" data-i18n="configurationMixer"></div>
</div> </div>
<div class="spacer_box"> <div class="spacer_box">
<div class="mixerPreview half"> <div class="mixerPreview half">
@ -29,7 +29,7 @@
<div class="rightWrapper motorstop"> <div class="rightWrapper motorstop">
<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="configurationEscFeatures"></div> <div class="spacer_box_title" data-i18n="configurationEscFeatures"></div>
</div> </div>
<div class="spacer_box"> <div class="spacer_box">
@ -42,15 +42,17 @@
<div id="esc-protocols"> <div id="esc-protocols">
<div class="select"> <div class="select">
<select name="esc-protocol" id="esc-protocol"></select> <select name="esc-protocol" id="esc-protocol"></select>
<label for="esc-protocol"> <span class="freelabel" <label for="esc-protocol">
i18n="escProtocol"></span></label> <span data-i18n="escProtocol"></span>
<div class="helpicon cf_tip" i18n_title="escProtocolHelp"></div> </label>
<div class="helpicon cf_tip" data-i18n_title="escProtocolHelp"></div>
</div> </div>
<div class="select"> <div class="select">
<select name="esc-rate" id="esc-rate"></select> <select name="esc-rate" id="esc-rate"></select>
<label for="esc-refresh-rate"> <span class="freelabel" <label for="esc-rate">
i18n="escRefreshRate"></span></label> <span data-i18n="escRefreshRate"></span>
<div class="helpicon cf_tip" i18n_title="escRefreshRatelHelp"></div> </label>
<div class="helpicon cf_tip" data-i18n_title="escRefreshRatelHelp"></div>
</div> </div>
<div class="clear-both"></div> <div class="clear-both"></div>
</div> </div>
@ -58,9 +60,10 @@
<div id="servo-rate-container"> <div id="servo-rate-container">
<div class="select"> <div class="select">
<select name="servo-rate" id="servo-rate"></select> <select name="servo-rate" id="servo-rate"></select>
<label for="servo-rate"> <span class="freelabel" <label for="servo-rate">
i18n="servoRefreshRate"></span></label> <span data-i18n="servoRefreshRate"></span>
<div class="helpicon cf_tip" i18n_title="servoRefreshRatelHelp"></div> </label>
<div class="helpicon cf_tip" data-i18n_title="servoRefreshRatelHelp"></div>
</div> </div>
<div class="clear-both"></div> <div class="clear-both"></div>
</div> </div>
@ -72,55 +75,45 @@
</table> </table>
<!-- --> <!-- -->
<div class="disarm"> <div class="checkbox">
<div class="checkbox"> <input type="checkbox" id="disarmkillswitch" name="disarmkillswitch" class="toggle" />
<div style="float: left; height: 20px; margin-right: 15px; margin-left: 3px;"> <label for="disarmkillswitch">
<input type="checkbox" name="disarmkillswitch" class="toggle" /> <span data-i18n="configurationDisarmKillSwitch"></span>
</div> </label>
<label for="disarmkillswitch"> <span class="freelabel" <div class="helpicon cf_tip" data-i18n_title="configurationDisarmKillSwitchHelp"></div>
i18n="configurationDisarmKillSwitch"></span>
</label>
</div>
<div class="number disarmdelay" style="display: none; margin-bottom: 5px;">
<label>
<div class="numberspacer">
<input type="number" name="autodisarmdelay" min="0" max="60" />
</div>
<span i18n="configurationAutoDisarmDelay"></span>
</label>
</div>
</div> </div>
<div class="number disarmdelay" style="display: none; margin-bottom: 5px;">
<input type="number" name="autodisarmdelay" min="0" max="60" />
<label>
<span data-i18n="configurationAutoDisarmDelay"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="configurationAutoDisarmDelayHelp"></div>
</div>
<!-- --> <!-- -->
<div class="number"> <div class="number">
<input type="number" name="minthrottle" min="0" max="2000" />
<label> <label>
<div class="numberspacer"> <span data-i18n="configurationThrottleMinimum"></span>
<input type="number" name="minthrottle" min="0" max="2000" />
</div>
<span i18n="configurationThrottleMinimum"></span>
</label> </label>
</div> </div>
<div class="number"> <div class="number">
<input type="number" name="midthrottle" min="0" max="2000" />
<label> <label>
<div class="numberspacer"> <span data-i18n="configurationThrottleMid"></span>
<input type="number" name="midthrottle" min="0" max="2000" />
</div>
<span i18n="configurationThrottleMid"></span>
</label> </label>
</div> </div>
<div class="number"> <div class="number">
<input type="number" name="maxthrottle" min="0" max="2000" />
<label> <label>
<div class="numberspacer"> <span data-i18n="configurationThrottleMaximum"></span>
<input type="number" name="maxthrottle" min="0" max="2000" />
</div>
<span i18n="configurationThrottleMaximum"></span>
</label> </label>
</div> </div>
<div class="number"> <div class="number">
<input type="number" name="mincommand" min="0" max="2000" />
<label> <label>
<div class="numberspacer"> <span data-i18n="configurationThrottleMinimumCommand"></span>
<input type="number" name="mincommand" min="0" max="2000" />
</div>
<span i18n="configurationThrottleMinimumCommand"></span>
</label> </label>
</div> </div>
</div> </div>
@ -130,26 +123,26 @@
<div class="leftWrapper board"> <div class="leftWrapper board">
<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" data-i18n="configurationBoardAlignment"></div>
<div class="helpicon cf_tip" i18n_title="configHelp2"></div> <div class="helpicon cf_tip" data-i18n_title="configHelp2"></div>
</div> </div>
<div class="spacer_box"> <div class="spacer_box">
<div class="board_align_content"> <div class="board_align_content">
<div class="number"> <div class="number">
<label> <input type="number" name="board_align_roll" step="0.1" min="-180" max="360" /> <span <label> <input type="number" name="board_align_roll" step="0.1" min="-180" max="360" /> <span
i18n="configurationBoardAlignmentRoll"></span> data-i18n="configurationBoardAlignmentRoll"></span>
</label> </label>
<div class="alignicon roll"></div> <div class="alignicon roll"></div>
</div> </div>
<div class="number"> <div class="number">
<label> <input type="number" name="board_align_pitch" step="0.1" min="-180" max="360" /> <label> <input type="number" name="board_align_pitch" step="0.1" min="-180" max="360" />
<span i18n="configurationBoardAlignmentPitch"></span> <span data-i18n="configurationBoardAlignmentPitch"></span>
</label> </label>
<div class="alignicon pitch"></div> <div class="alignicon pitch"></div>
</div> </div>
<div class="number"> <div class="number">
<label> <input type="number" name="board_align_yaw" step="0.1" min="-180" max="360" /> <span <label> <input type="number" name="board_align_yaw" step="0.1" min="-180" max="360" /> <span
i18n="configurationBoardAlignmentYaw"></span> data-i18n="configurationBoardAlignmentYaw"></span>
</label> </label>
<div class="alignicon yaw"></div> <div class="alignicon yaw"></div>
</div> </div>
@ -157,7 +150,7 @@
<div class="sensoralignment"> <div class="sensoralignment">
<div class="select"> <div class="select">
<label> <label>
<span i18n="configurationSensorAlignmentGyro"></span> <span data-i18n="configurationSensorAlignmentGyro"></span>
<select class="gyroalign"> <select class="gyroalign">
<option value="0">Default</option> <option value="0">Default</option>
<!-- list generated here --> <!-- list generated here -->
@ -166,7 +159,7 @@
</div> </div>
<div class="select"> <div class="select">
<label> <label>
<span i18n="configurationSensorAlignmentAcc"></span> <span data-i18n="configurationSensorAlignmentAcc"></span>
<select class="accalign"> <select class="accalign">
<option value="0">Default</option> <option value="0">Default</option>
<!-- list generated here --> <!-- list generated here -->
@ -175,7 +168,7 @@
</div> </div>
<div class="select"> <div class="select">
<label> <label>
<span i18n="configurationSensorAlignmentMag"></span> <span data-i18n="configurationSensorAlignmentMag"></span>
<select class="magalign"> <select class="magalign">
<option value="0">Default</option> <option value="0">Default</option>
<!-- list generated here --> <!-- list generated here -->
@ -189,30 +182,59 @@
<div class="rightWrapper system"> <div class="rightWrapper system">
<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="configurationSystem"></div> <div class="spacer_box_title" data-i18n="configurationSystem"></div>
</div> </div>
<div class="spacer_box"> <div class="spacer_box">
<div class="checkbox requires-v1_4"> <div class="select requires-v1_4">
<div class="numberspacer"> <select id="gyro-lpf"></select>
<input type="checkbox" id="gyro-sync-checkbox" class="toggle" /> <label for="gyro-lpf"> <span data-i18n="configurationGyroLpfTitle"></span></label>
</div> <div class="helpicon cf_tip" data-i18n_title="configurationGyroLpfHelp"></div>
<label> <span i18n="configurationGyroSyncTitle"></span> </div>
<div class="select requires-v1_4">
<select id="async-mode"></select>
<label for="async-mode"> <span data-i18n="configurationAsyncMode"></span></label>
<div class="helpicon cf_tip" data-i18n_title="configurationAsyncModeHelp"></div>
</div>
<div id="gyro-sync-wrapper" class="checkbox requires-v1_4">
<input type="checkbox" id="gyro-sync-checkbox" class="toggle" />
<label for="gyro-sync-checkbox">
<span data-i18n="configurationGyroSyncTitle"></span>
</label> </label>
</div> </div>
<hr class="requires-v1_4" /> <div id="gyro-frequency-wrapper" class="checkbox requires-v1_4">
<select id="gyro-frequency"></select>
<label for="gyro-frequency">
<span data-i18n="configurationGyroFrequencyTitle"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="configurationGyroFrequencyHelp"></div>
</div>
<div class="select requires-v1_4"> <div id="accelerometer-frequency-wrapper" class="checkbox requires-v1_4">
<select id="gyro-lpf"></select> <select id="accelerometer-frequency"></select>
<label for="gyro-lpf"> <span i18n="configurationGyroLpfTitle"></span></label> <label for="accelerometer-frequency">
<span data-i18n="configurationAccelerometerFrequencyTitle"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="configurationAccelerometerFrequencyHelp"></div>
</div>
<div id="attitude-frequency-wrapper" class="checkbox requires-v1_4">
<select id="attitude-frequency"></select>
<label for="attitude-frequency">
<span data-i18n="configurationAttitudeFrequencyTitle"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="configurationAttitudeFrequencyHelp"></div>
</div> </div>
<div class="select"> <div class="select">
<select id="looptime"></select> <select id="looptime"></select>
<label for="looptime"> <span <label for="looptime">
i18n="configurationLoopTime"></span> <span data-i18n="configurationLoopTime"></span>
</label> </label>
<div class="helpicon cf_tip" data-i18n_title="configurationLoopTimeHelp"></div>
</div> </div>
</div> </div>
</div> </div>
@ -221,15 +243,15 @@
<div class="leftWrapper"> <div class="leftWrapper">
<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="configurationReceiver"></div> <div class="spacer_box_title" data-i18n="configurationReceiver"></div>
</div> </div>
<div class="spacer_box"> <div class="spacer_box">
<table cellpadding="0" cellspacing="0"> <table cellpadding="0" cellspacing="0">
<thead> <thead>
<tr> <tr>
<th i18n="configurationFeatureEnabled"></th> <th data-i18n="configurationFeatureEnabled"></th>
<th i18n="configurationFeatureDescription"></th> <th data-i18n="configurationFeatureDescription"></th>
<th i18n="configurationFeatureName"></th> <th data-i18n="configurationFeatureName"></th>
</tr> </tr>
</thead> </thead>
<tbody class="features rxMode"> <tbody class="features rxMode">
@ -240,25 +262,25 @@
</div> </div>
<div class="gui_box grey rxprovider"> <div class="gui_box grey rxprovider">
<div class="gui_box_titlebar"> <div class="gui_box_titlebar">
<div class="spacer_box_title" i18n="configurationSerialRX"></div> <div class="spacer_box_title" data-i18n="configurationSerialRX"></div>
</div> </div>
<div class="spacer_box"> <div class="spacer_box">
<div class="note"> <div class="note">
<div class="note_spacer"> <div class="note_spacer">
<p i18n="configurationSerialRXHelp"></p> <p data-i18n="configurationSerialRXHelp"></p>
</div> </div>
</div> </div>
<select class="serialRX" size="8"> <select class="serialRX" size="4">
<!-- list generated here --> <!-- list generated here -->
</select> </select>
</div> </div>
</div> </div>
<div class="gui_box grey nrf24provider"> <div class="gui_box grey nrf24provider">
<div class="gui_box_titlebar"> <div class="gui_box_titlebar">
<div class="spacer_box_title" i18n="configurationNrf24Protocol"></div> <div class="spacer_box_title" data-i18n="configurationNrf24Protocol"></div>
</div> </div>
<div class="spacer_box"> <div class="spacer_box">
<select class="nrf24Protocol" size="8"> <select class="nrf24Protocol" size="4">
<!-- list generated here --> <!-- list generated here -->
</select> </select>
</div> </div>
@ -267,15 +289,15 @@
<div class="rightWrapper current voltage"> <div class="rightWrapper current voltage">
<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="configurationBatteryVoltage"></div> <div class="spacer_box_title" data-i18n="configurationBatteryVoltage"></div>
</div> </div>
<div class="spacer_box"> <div class="spacer_box">
<table cellpadding="0" cellspacing="0"> <table cellpadding="0" cellspacing="0">
<thead> <thead>
<tr> <tr>
<th i18n="configurationFeatureEnabled"></th> <th data-i18n="configurationFeatureEnabled"></th>
<th i18n="configurationFeatureDescription"></th> <th data-i18n="configurationFeatureDescription"></th>
<th i18n="configurationFeatureName"></th> <th data-i18n="configurationFeatureName"></th>
</tr> </tr>
</thead> </thead>
<tbody class="features batteryVoltage"> <tbody class="features batteryVoltage">
@ -284,42 +306,42 @@
</table> </table>
<div class="number"> <div class="number">
<label> <input type="number" name="mincellvoltage" step="0.1" min="1" max="5" /> <span <label> <input type="number" name="mincellvoltage" step="0.1" min="1" max="5" /> <span
i18n="configurationBatteryMinimum"></span> data-i18n="configurationBatteryMinimum"></span>
</label> </label>
</div> </div>
<div class="number"> <div class="number">
<label> <input type="number" name="maxcellvoltage" step="0.1" min="1" max="5" /> <span <label> <input type="number" name="maxcellvoltage" step="0.1" min="1" max="5" /> <span
i18n="configurationBatteryMaximum"></span> data-i18n="configurationBatteryMaximum"></span>
</label> </label>
</div> </div>
<div class="number"> <div class="number">
<label> <input type="number" name="warningcellvoltage" step="0.1" min="1" max="5" /> <span <label> <input type="number" name="warningcellvoltage" step="0.1" min="1" max="5" /> <span
i18n="configurationBatteryWarning"></span> data-i18n="configurationBatteryWarning"></span>
</label> </label>
</div> </div>
<div class="number"> <div class="number">
<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> data-i18n="configurationBatteryScale"></span>
</label> </label>
</div> </div>
<div class="number"> <div class="number">
<label> <input type="text" name="batteryvoltage" readonly class="disabled" /> <span <label> <input type="text" name="batteryvoltage" readonly class="disabled" /> <span
i18n="configurationBatteryVoltage"></span> data-i18n="configurationBatteryVoltage"></span>
</label> </label>
</div> </div>
</div> </div>
</div> </div>
<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="configurationCurrent"></div> <div class="spacer_box_title" data-i18n="configurationCurrent"></div>
</div> </div>
<div class="spacer_box"> <div class="spacer_box">
<table cellpadding="0" cellspacing="0"> <table cellpadding="0" cellspacing="0">
<thead> <thead>
<tr> <tr>
<th i18n="configurationFeatureEnabled"></th> <th data-i18n="configurationFeatureEnabled"></th>
<th i18n="configurationFeatureDescription"></th> <th data-i18n="configurationFeatureDescription"></th>
<th i18n="configurationFeatureName"></th> <th data-i18n="configurationFeatureName"></th>
</tr> </tr>
</thead> </thead>
<tbody class="features batteryCurrent"> <tbody class="features batteryCurrent">
@ -328,23 +350,24 @@
</table> </table>
<div class="number"> <div class="number">
<label> <input type="number" name="currentscale" step="1" min="-1000" max="1000" /> <span <label> <input type="number" name="currentscale" step="1" min="-1000" max="1000" /> <span
i18n="configurationCurrentScale"></span> data-i18n="configurationCurrentScale"></span>
</label> </label>
</div> </div>
<div class="number"> <div class="number">
<label> <input type="number" name="currentoffset" step="1" min="0" max="3300" /> <span <label> <input type="number" name="currentoffset" step="1" min="0" max="3300" /> <span
i18n="configurationCurrentOffset"></span> data-i18n="configurationCurrentOffset"></span>
</label> </label>
</div> </div>
<div class="number"> <div class="number">
<label> <input type="text" name="batterycurrent" readonly class="disabled" /> <span <label> <input type="text" name="batterycurrent" readonly class="disabled" /> <span
i18n="configurationBatteryCurrent"></span> data-i18n="configurationBatteryCurrent"></span>
</label>
</div> </div>
<div class="checkbox"> <div class="checkbox">
<div class="numberspacer"> <div class="numberspacer">
<input type="checkbox" name="multiwiicurrentoutput" class="toggle" /> <input type="checkbox" name="multiwiicurrentoutput" class="toggle" />
</div> </div>
<label> <span i18n="configurationBatteryMultiwiiCurrent"></span> <label> <span data-i18n="configurationBatteryMultiwiiCurrent"></span>
</label> </label>
</div> </div>
</div> </div>
@ -354,20 +377,20 @@
<div class="leftWrapper gps"> <div class="leftWrapper gps">
<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="configurationGPS"></div> <div class="spacer_box_title" data-i18n="configurationGPS"></div>
</div> </div>
<div class="spacer_box"> <div class="spacer_box">
<div class="note"> <div class="note">
<div class="note_spacer"> <div class="note_spacer">
<p i18n="configurationGPSHelp"></p> <p data-i18n="configurationGPSHelp"></p>
</div> </div>
</div> </div>
<table cellpadding="0" cellspacing="0"> <table cellpadding="0" cellspacing="0">
<thead> <thead>
<tr> <tr>
<th i18n="configurationFeatureEnabled"></th> <th data-i18n="configurationFeatureEnabled"></th>
<th i18n="configurationFeatureDescription"></th> <th data-i18n="configurationFeatureDescription"></th>
<th i18n="configurationFeatureName"></th> <th data-i18n="configurationFeatureName"></th>
</tr> </tr>
</thead> </thead>
<tbody class="features gps"> <tbody class="features gps">
@ -378,23 +401,17 @@
<select class="gps_protocol"> <select class="gps_protocol">
<!-- list generated here --> <!-- list generated here -->
</select> </select>
<span i18n="configurationGPSProtocol"></span> <span data-i18n="configurationGPSProtocol"></span>
</div>
<div class="line">
<select class="gps_baudrate">
<!-- list generated here -->
</select>
<span i18n="configurationGPSBaudrate"></span>
</div> </div>
<div class="line"> <div class="line">
<select class="gps_ubx_sbas"> <select class="gps_ubx_sbas">
<!-- list generated here --> <!-- list generated here -->
</select> </select>
<span i18n="configurationGPSubxSbas"></span> <span data-i18n="configurationGPSubxSbas"></span>
</div> </div>
<div class="number"> <div class="number">
<label> <input type="number" name="mag_declination" step="0.1" min="-180" max="180" /> <label> <input type="number" name="mag_declination" step="0.1" min="-180" max="180" />
<span i18n="configurationMagDeclination"></span> <span data-i18n="configurationMagDeclination"></span>
</label> </label>
</div> </div>
</div> </div>
@ -403,15 +420,15 @@
<div class="rightWrapper other"> <div class="rightWrapper other">
<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" data-i18n="configurationFeatures"></div>
</div> </div>
<div class="spacer_box"> <div class="spacer_box">
<table cellpadding="0" cellspacing="0"> <table cellpadding="0" cellspacing="0">
<thead> <thead>
<tr> <tr>
<th i18n="configurationFeatureEnabled"></th> <th data-i18n="configurationFeatureEnabled"></th>
<th i18n="configurationFeatureDescription"></th> <th data-i18n="configurationFeatureDescription"></th>
<th i18n="configurationFeatureName"></th> <th data-i18n="configurationFeatureName"></th>
</tr> </tr>
</thead> </thead>
<tbody class="features other" id="noline"> <tbody class="features other" id="noline">
@ -424,16 +441,16 @@
<div class="leftWrapper rssi"> <div class="leftWrapper rssi">
<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="configurationRSSI"></div> <div class="spacer_box_title" data-i18n="configurationRSSI"></div>
<div class="helpicon cf_tip" i18n_title="configurationRSSIHelp"></div> <div class="helpicon cf_tip" data-i18n_title="configurationRSSIHelp"></div>
</div> </div>
<div class="spacer_box"> <div class="spacer_box">
<table cellpadding="0" cellspacing="0"> <table cellpadding="0" cellspacing="0">
<thead> <thead>
<tr> <tr>
<th i18n="configurationFeatureEnabled"></th> <th data-i18n="configurationFeatureEnabled"></th>
<th i18n="configurationFeatureDescription"></th> <th data-i18n="configurationFeatureDescription"></th>
<th i18n="configurationFeatureName"></th> <th data-i18n="configurationFeatureName"></th>
</tr> </tr>
</thead> </thead>
<tbody class="features rssi"> <tbody class="features rssi">
@ -446,27 +463,27 @@
<div class="rightWrapper 3d"> <div class="rightWrapper 3d">
<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="configuration3d"></div> <div class="spacer_box_title" data-i18n="configuration3d"></div>
</div> </div>
<div class="spacer_box"> <div class="spacer_box">
<div class="number"> <div class="number">
<label> <input type="number" name="3ddeadbandlow" step="1" min="1425" max="1500" /> <span <label> <input type="number" name="3ddeadbandlow" step="1" min="1425" max="1500" /> <span
i18n="configuration3dDeadbandLow"></span> data-i18n="configuration3dDeadbandLow"></span>
</label> </label>
</div> </div>
<div class="number"> <div class="number">
<label> <input type="number" name="3ddeadbandhigh" step="1" min="1500" max="1575" /> <span <label> <input type="number" name="3ddeadbandhigh" step="1" min="1500" max="1575" /> <span
i18n="configuration3dDeadbandHigh"></span> data-i18n="configuration3dDeadbandHigh"></span>
</label> </label>
</div> </div>
<div class="number"> <div class="number">
<label> <input type="number" name="3dneutral" step="1" min="1475" max="1525" /> <span <label> <input type="number" name="3dneutral" step="1" min="1475" max="1525" /> <span
i18n="configuration3dNeutral"></span> data-i18n="configuration3dNeutral"></span>
</label> </label>
</div> </div>
<div class="number 3ddeadbandthrottle" > <div class="number 3ddeadbandthrottle" >
<label> <input type="number" name="3ddeadbandthrottle" step="1" min="0" max="1000" /> <span <label> <input type="number" name="3ddeadbandthrottle" step="1" min="0" max="1000" /> <span
i18n="configuration3dDeadbandThrottle"></span> data-i18n="configuration3dDeadbandThrottle"></span>
</label> </label>
</div> </div>
</div> </div>
@ -476,7 +493,7 @@
</div> </div>
<div class="content_toolbar"> <div class="content_toolbar">
<div class="btn save_btn"> <div class="btn save_btn">
<a class="save" href="#" i18n="configurationButtonSave"></a> <a class="save" href="#" data-i18n="configurationButtonSave"></a>
</div> </div>
</div> </div>
</div> </div>

View file

@ -3,7 +3,6 @@
TABS.configuration = {}; TABS.configuration = {};
TABS.configuration.initialize = function (callback, scrollPosition) { TABS.configuration.initialize = function (callback, scrollPosition) {
var self = this;
if (GUI.active_tab != 'configuration') { if (GUI.active_tab != 'configuration') {
GUI.active_tab = 'configuration'; GUI.active_tab = 'configuration';
@ -11,20 +10,7 @@ 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_BF_CONFIG, false, false, load_misc);
}
function load_serial_config() {
var next_callback = load_rc_map;
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_rc_map() {
MSP.send_message(MSPCodes.MSP_RX_MAP, false, false, load_misc);
} }
function load_misc() { function load_misc() {
@ -32,21 +18,11 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
} }
function load_arming_config() { function load_arming_config() {
var next_callback = load_loop_time; MSP.send_message(MSPCodes.MSP_ARMING_CONFIG, false, false, 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() { function load_loop_time() {
var next_callback = load_rx_config; MSP.send_message(MSPCodes.MSP_LOOP_TIME, false, false, load_rx_config);
if (semver.gte(CONFIG.apiVersion, "1.8.0")) {
MSP.send_message(MSPCodes.MSP_LOOP_TIME, false, false, next_callback);
} else {
next_callback();
}
} }
function load_rx_config() { function load_rx_config() {
@ -59,21 +35,11 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
} }
function load_3d() { function load_3d() {
var next_callback = load_sensor_alignment; MSP.send_message(MSPCodes.MSP_3D, false, false, load_sensor_alignment);
if (semver.gte(CONFIG.apiVersion, "1.14.0")) {
MSP.send_message(MSPCodes.MSP_3D, false, false, next_callback);
} else {
next_callback();
}
} }
function load_sensor_alignment() { function load_sensor_alignment() {
var next_callback = loadAdvancedConfig; MSP.send_message(MSPCodes.MSP_SENSOR_ALIGNMENT, false, false, loadAdvancedConfig);
if (semver.gte(CONFIG.apiVersion, "1.15.0")) {
MSP.send_message(MSPCodes.MSP_SENSOR_ALIGNMENT, false, false, next_callback);
} else {
next_callback();
}
} }
function loadAdvancedConfig() { function loadAdvancedConfig() {
@ -110,13 +76,15 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
function process_html() { function process_html() {
var i;
var mixer_list_e = $('select.mixerList'); var mixer_list_e = $('select.mixerList');
for (var i = 0; i < mixerList.length; i++) { for (i = 0; i < mixerList.length; i++) {
mixer_list_e.append('<option value="' + (i + 1) + '">' + mixerList[i].name + '</option>'); mixer_list_e.append('<option value="' + (i + 1) + '">' + mixerList[i].name + '</option>');
} }
mixer_list_e.change(function () { mixer_list_e.change(function () {
var val = parseInt($(this).val()); var val = parseInt($(this).val(), 10);
BF_CONFIG.mixerConfiguration = val; BF_CONFIG.mixerConfiguration = val;
@ -132,7 +100,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
var radioGroups = []; var radioGroups = [];
var features_e = $('.features'); var features_e = $('.features');
for (var i = 0; i < features.length; i++) { for (i = 0; i < features.length; i++) {
var row_e; var row_e;
var feature_tip_html = ''; var feature_tip_html = '';
@ -153,7 +121,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
+ i + i
+ '">' + '">'
+ features[i].name + features[i].name
+ '</label></td><td><span i18n="feature' + features[i].name + '"></span>' + '</label></td><td><span data-i18n="feature' + features[i].name + '"></span>'
+ feature_tip_html + '</td></tr>'); + feature_tip_html + '</td></tr>');
radioGroups.push(features[i].group); radioGroups.push(features[i].group);
} else { } else {
@ -167,7 +135,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
+ i + i
+ '">' + '">'
+ features[i].name + features[i].name
+ '</label></td><td><span i18n="feature' + features[i].name + '"></span>' + '</label></td><td><span data-i18n="feature' + features[i].name + '"></span>'
+ feature_tip_html + '</td></tr>'); + feature_tip_html + '</td></tr>');
var feature_e = row_e.find('input.feature'); var feature_e = row_e.find('input.feature');
@ -186,7 +154,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
// translate to user-selected language // translate to user-selected language
localize(); localize();
for (var i = 0; i < radioGroups.length; i++) { for (i = 0; i < radioGroups.length; i++) {
var group = radioGroups[i]; var group = radioGroups[i];
var controls_e = $('input[name="' + group + '"].feature'); var controls_e = $('input[name="' + group + '"].feature');
@ -200,62 +168,27 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
} }
var alignments = [ var alignments = FC.getSensorAlignments();
'CW 0°',
'CW 90°',
'CW 180°',
'CW 270°',
'CW 0° flip',
'CW 90° flip',
'CW 180° flip',
'CW 270° flip'
];
var orientation_gyro_e = $('select.gyroalign'); var orientation_gyro_e = $('select.gyroalign');
var orientation_acc_e = $('select.accalign'); var orientation_acc_e = $('select.accalign');
var orientation_mag_e = $('select.magalign'); var orientation_mag_e = $('select.magalign');
if (semver.lt(CONFIG.apiVersion, "1.15.0")) { for (i = 0; i < alignments.length; i++) {
$('.tab-configuration .sensoralignment').hide(); orientation_gyro_e.append('<option value="' + (i+1) + '">'+ alignments[i] + '</option>');
} else { orientation_acc_e.append('<option value="' + (i+1) + '">'+ alignments[i] + '</option>');
for (var i = 0; i < alignments.length; i++) { orientation_mag_e.append('<option value="' + (i+1) + '">'+ alignments[i] + '</option>');
orientation_gyro_e.append('<option value="' + (i+1) + '">'+ alignments[i] + '</option>');
orientation_acc_e.append('<option value="' + (i+1) + '">'+ alignments[i] + '</option>');
orientation_mag_e.append('<option value="' + (i+1) + '">'+ alignments[i] + '</option>');
}
orientation_gyro_e.val(SENSOR_ALIGNMENT.align_gyro);
orientation_acc_e.val(SENSOR_ALIGNMENT.align_acc);
orientation_mag_e.val(SENSOR_ALIGNMENT.align_mag);
} }
orientation_gyro_e.val(SENSOR_ALIGNMENT.align_gyro);
orientation_acc_e.val(SENSOR_ALIGNMENT.align_acc);
orientation_mag_e.val(SENSOR_ALIGNMENT.align_mag);
// generate GPS // generate GPS
var gpsProtocols = [ var gpsProtocols = FC.getGpsProtocols();
'NMEA', var gpsSbas = FC.getGpsSbasProviders();
'UBLOX',
'I2C-NAV',
'DJI NAZA',
];
var gpsBaudRates = [
'115200',
'57600',
'38400',
'19200',
'9600'
];
var gpsSbas = [
'Autodetect',
'European EGNOS',
'North American WAAS',
'Japanese MSAS',
'Indian GAGAN',
'Disabled',
];
var gps_protocol_e = $('select.gps_protocol'); var gps_protocol_e = $('select.gps_protocol');
for (var i = 0; i < gpsProtocols.length; i++) { for (i = 0; i < gpsProtocols.length; i++) {
gps_protocol_e.append('<option value="' + i + '">' + gpsProtocols[i] + '</option>'); gps_protocol_e.append('<option value="' + i + '">' + gpsProtocols[i] + '</option>');
} }
@ -265,24 +198,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
gps_protocol_e.val(MISC.gps_type); gps_protocol_e.val(MISC.gps_type);
var gps_baudrate_e = $('select.gps_baudrate');
for (var i = 0; i < gpsBaudRates.length; i++) {
gps_baudrate_e.append('<option value="' + gpsBaudRates[i] + '">' + gpsBaudRates[i] + '</option>');
}
if (semver.lt(CONFIG.apiVersion, "1.6.0")) {
gps_baudrate_e.change(function () {
SERIAL_CONFIG.gpsBaudRate = parseInt($(this).val());
});
gps_baudrate_e.val(SERIAL_CONFIG.gpsBaudRate);
} else {
gps_baudrate_e.prop("disabled", true);
gps_baudrate_e.parent().hide();
}
var gps_ubx_sbas_e = $('select.gps_ubx_sbas'); var gps_ubx_sbas_e = $('select.gps_ubx_sbas');
for (var i = 0; i < gpsSbas.length; i++) { for (i = 0; i < gpsSbas.length; i++) {
gps_ubx_sbas_e.append('<option value="' + i + '">' + gpsSbas[i] + '</option>'); gps_ubx_sbas_e.append('<option value="' + i + '">' + gpsSbas[i] + '</option>');
} }
@ -294,20 +211,11 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
// generate serial RX // generate serial RX
var serialRXtypes = [ var serialRxTypes = FC.getSerialRxTypes();
'SPEKTRUM1024',
'SPEKTRUM2048',
'SBUS',
'SUMD',
'SUMH',
'XBUS_MODE_B',
'XBUS_MODE_B_RJ01',
'IBUS'
];
var serialRX_e = $('select.serialRX'); var serialRX_e = $('select.serialRX');
for (var i = 0; i < serialRXtypes.length; i++) { for (i = 0; i < serialRxTypes.length; i++) {
serialRX_e.append('<option value="' + i + '">' + serialRXtypes[i] + '</option>'); serialRX_e.append('<option value="' + i + '">' + serialRxTypes[i] + '</option>');
} }
serialRX_e.change(function () { serialRX_e.change(function () {
@ -320,22 +228,14 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
// for some odd reason chrome 38+ changes scroll according to the touched select element // for some odd reason chrome 38+ changes scroll according to the touched select element
// i am guessing this is a bug, since this wasn't happening on 37 // i am guessing this is a bug, since this wasn't happening on 37
// code below is a temporary fix, which we will be able to remove in the future (hopefully) // code below is a temporary fix, which we will be able to remove in the future (hopefully)
//noinspection JSValidateTypes
$('#content').scrollTop((scrollPosition) ? scrollPosition : 0); $('#content').scrollTop((scrollPosition) ? scrollPosition : 0);
var nrf24Protocoltypes = [ var nrf24ProtocolTypes = FC.getNrf24ProtocolTypes();
'V202 250Kbps',
'V202 1Mbps',
'Syma X',
'Syma X5C',
'Cheerson CX10',
'Cheerson CX10A',
'JJRC H8_3D',
'iNav Reference protocol'
];
var nrf24Protocol_e = $('select.nrf24Protocol'); var nrf24Protocol_e = $('select.nrf24Protocol');
for (var i = 0; i < nrf24Protocoltypes.length; i++) { for (i = 0; i < nrf24ProtocolTypes.length; i++) {
nrf24Protocol_e.append('<option value="' + i + '">' + nrf24Protocoltypes[i] + '</option>'); nrf24Protocol_e.append('<option value="' + i + '">' + nrf24ProtocolTypes[i] + '</option>');
} }
nrf24Protocol_e.change(function () { nrf24Protocol_e.change(function () {
@ -355,15 +255,13 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
$('input[name="mag_declination"]').val(MISC.mag_declination); $('input[name="mag_declination"]').val(MISC.mag_declination);
//fill motor disarm params and FC loop time //fill motor disarm params and FC loop time
if(semver.gte(CONFIG.apiVersion, "1.8.0")) { $('input[name="autodisarmdelay"]').val(ARMING_CONFIG.auto_disarm_delay);
$('input[name="autodisarmdelay"]').val(ARMING_CONFIG.auto_disarm_delay); $('input[name="disarmkillswitch"]').prop('checked', ARMING_CONFIG.disarm_kill_switch);
$('input[name="disarmkillswitch"]').prop('checked', ARMING_CONFIG.disarm_kill_switch); $('div.disarm').show();
$('div.disarm').show(); if(bit_check(BF_CONFIG.features, 4)) {//MOTOR_STOP
if(bit_check(BF_CONFIG.features, 4))//MOTOR_STOP $('div.disarmdelay').show();
$('div.disarmdelay').show(); } else {
else $('div.disarmdelay').hide();
$('div.disarmdelay').hide();
} }
// fill throttle // fill throttle
@ -383,64 +281,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
$('input[name="currentoffset"]').val(BF_CONFIG.currentoffset); $('input[name="currentoffset"]').val(BF_CONFIG.currentoffset);
$('input[name="multiwiicurrentoutput"]').prop('checked', MISC.multiwiicurrentoutput); $('input[name="multiwiicurrentoutput"]').prop('checked', MISC.multiwiicurrentoutput);
var escProtocols = { var escProtocols = FC.getEscProtocols();
0: { var servoRates = FC.getServoRates();
name: "STANDARD",
defaultRate: 400,
rates: {
50: "50Hz",
400: "400Hz"
}
},
1: {
name: "ONESHOT125",
defaultRate: 1000,
rates: {
400: "400Hz",
1000: "1kHz",
2000: "2kHz"
}
},
2: {
name: "ONESHOT42",
defaultRate: 2000,
rates: {
400: "400Hz",
1000: "1kHz",
2000: "2kHz",
4000: "4kHz",
8000: "8kHz"
}
},
3: {
name: "MULTISHOT",
defaultRate: 2000,
rates: {
400: "400Hz",
1000: "1kHz",
2000: "2kHz",
4000: "4kHz",
8000: "8kHz"
}
},
4: {
name: "BRUSHED",
defaultRate: 8000,
rates: {
8000: "8kHz",
16000: "16kHz",
32000: "32kHz"
}
}
};
var servoRates = {
50: "50Hz",
60: "60Hz",
100: "100Hz",
200: "200Hz",
400: "400Hz"
};
function buildMotorRates() { function buildMotorRates() {
var protocolData = escProtocols[ADVANCED_CONFIG.motorPwmProtocol]; var protocolData = escProtocols[ADVANCED_CONFIG.motorPwmProtocol];
@ -466,7 +308,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
var $escProtocol = $('#esc-protocol'); var $escProtocol = $('#esc-protocol');
var $escRate = $('#esc-rate'); var $escRate = $('#esc-rate');
for (var i in escProtocols) { for (i in escProtocols) {
if (escProtocols.hasOwnProperty(i)) { if (escProtocols.hasOwnProperty(i)) {
var protocolData = escProtocols[i]; var protocolData = escProtocols[i];
$escProtocol.append('<option value="' + i + '">' + protocolData.name + '</option>'); $escProtocol.append('<option value="' + i + '">' + protocolData.name + '</option>');
@ -492,7 +334,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
var $servoRate = $('#servo-rate'); var $servoRate = $('#servo-rate');
for (var i in servoRates) { for (i in servoRates) {
if (servoRates.hasOwnProperty(i)) { if (servoRates.hasOwnProperty(i)) {
$servoRate.append('<option value="' + i + '">' + servoRates[i] + '</option>'); $servoRate.append('<option value="' + i + '">' + servoRates[i] + '</option>');
} }
@ -512,18 +354,46 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
$('#servo-rate-container').show(); $('#servo-rate-container').show();
} }
var gyroLpfValues = FC.getGyroLpfValues();
var looptimes = FC.getLooptimes();
var $looptime = $("#looptime"); var $looptime = $("#looptime");
//TODO move this up and use in more places
var fillSelect = function ($element, values, currentValue, unit) {
if (unit == null) {
unit = '';
}
$element.find("*").remove();
for (i in values) {
if (values.hasOwnProperty(i)) {
$element.append('<option value="' + i + '">' + values[i] + '</option>');
}
}
/*
* If current Value is not on the list, add a new entry
*/
if (currentValue != null && $element.find('[value="' + currentValue + '"]').length == 0) {
$element.append('<option value="' + currentValue + '">' + currentValue + unit + '</option>');
}
};
if (semver.gte(CONFIG.flightControllerVersion, "1.4.0")) { if (semver.gte(CONFIG.flightControllerVersion, "1.4.0")) {
$(".requires-v1_4").show();
var $gyroLpf = $("#gyro-lpf"), var $gyroLpf = $("#gyro-lpf"),
$gyroSync = $("#gyro-sync-checkbox"); $gyroSync = $("#gyro-sync-checkbox"),
$asyncMode = $('#async-mode'),
$gyroFrequency = $('#gyro-frequency'),
$accelerometerFrequency = $('#accelerometer-frequency'),
$attitudeFrequency = $('#attitude-frequency');
for (var i in gyroLpfValues) { var values = FC.getGyroLpfValues();
if (gyroLpfValues.hasOwnProperty(i)) {
$gyroLpf.append('<option value="' + i + '">' + gyroLpfValues[i].label + '</option>'); for (i in values) {
if (values.hasOwnProperty(i)) {
//noinspection JSUnfilteredForInLoop
$gyroLpf.append('<option value="' + i + '">' + values[i].label + '</option>');
} }
} }
@ -533,34 +403,38 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
$gyroLpf.change(function () { $gyroLpf.change(function () {
INAV_PID_CONFIG.gyroscopeLpf = $gyroLpf.val(); INAV_PID_CONFIG.gyroscopeLpf = $gyroLpf.val();
$looptime.find("*").remove(); fillSelect(
var looptimeOptions = looptimes[gyroLpfValues[INAV_PID_CONFIG.gyroscopeLpf].tick]; $looptime,
for (var i in looptimeOptions.looptimes) { FC.getLooptimes()[FC.getGyroLpfValues()[INAV_PID_CONFIG.gyroscopeLpf].tick].looptimes,
if (looptimeOptions.looptimes.hasOwnProperty(i)) { FC_CONFIG.loopTime,
$looptime.append('<option value="' + i + '">' + looptimeOptions.looptimes[i] + '</option>'); 'Hz'
} );
} $looptime.val(FC.getLooptimes()[FC.getGyroLpfValues()[INAV_PID_CONFIG.gyroscopeLpf].tick].defaultLooptime);
$looptime.val(looptimeOptions.defaultLooptime);
$looptime.change(); $looptime.change();
fillSelect($gyroFrequency, FC.getGyroFrequencies()[FC.getGyroLpfValues()[INAV_PID_CONFIG.gyroscopeLpf].tick].looptimes);
$gyroFrequency.val(FC.getLooptimes()[FC.getGyroLpfValues()[INAV_PID_CONFIG.gyroscopeLpf].tick].defaultLooptime);
$gyroFrequency.change();
}); });
$gyroLpf.change() $gyroLpf.change();
$looptime.val(FC_CONFIG.loopTime);
$looptime.val(FC_CONFIG.loopTime);
$looptime.change(function () { $looptime.change(function () {
FC_CONFIG.loopTime = $(this).val();
if (INAV_PID_CONFIG.asynchronousMode == 0) { if (INAV_PID_CONFIG.asynchronousMode == 0) {
//All task running together //All task running together
FC_CONFIG.loopTime = $(this).val(); ADVANCED_CONFIG.gyroSyncDenominator = Math.floor(FC_CONFIG.loopTime / FC.getGyroLpfValues()[INAV_PID_CONFIG.gyroscopeLpf].tick);
ADVANCED_CONFIG.gyroSyncDenominator = Math.floor(FC_CONFIG.loopTime / gyroLpfValues[INAV_PID_CONFIG.gyroscopeLpf].tick);
} else {
//FIXME this is temporaty fix that gives the same functionality to ASYNC_MODE=GYRO and ALL
FC_CONFIG.loopTime = $(this).val();
ADVANCED_CONFIG.gyroSyncDenominator = Math.floor(FC_CONFIG.loopTime / gyroLpfValues[INAV_PID_CONFIG.gyroscopeLpf].tick);
} }
}); });
$looptime.change(); $looptime.change();
$gyroFrequency.val(ADVANCED_CONFIG.gyroSyncDenominator * FC.getGyroLpfValues()[INAV_PID_CONFIG.gyroscopeLpf].tick);
$gyroFrequency.change(function () {
ADVANCED_CONFIG.gyroSyncDenominator = Math.floor($gyroFrequency.val() / FC.getGyroLpfValues()[INAV_PID_CONFIG.gyroscopeLpf].tick);
});
$gyroSync.change(function () { $gyroSync.change(function () {
if ($(this).is(":checked")) { if ($(this).is(":checked")) {
ADVANCED_CONFIG.gyroSync = 1; ADVANCED_CONFIG.gyroSync = 1;
@ -571,14 +445,50 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
$gyroSync.change(); $gyroSync.change();
$(".requires-v1_4").show(); /*
} else { * Async mode select
var looptimeOptions = looptimes[125]; */
for (var i in looptimeOptions.looptimes) { fillSelect($asyncMode, FC.getAsyncModes());
if (looptimeOptions.looptimes.hasOwnProperty(i)) { $asyncMode.val(INAV_PID_CONFIG.asynchronousMode);
$looptime.append('<option value="' + i + '">' + looptimeOptions.looptimes[i] + '</option>'); $asyncMode.change(function () {
INAV_PID_CONFIG.asynchronousMode = $asyncMode.val();
if (INAV_PID_CONFIG.asynchronousMode == 0) {
$('#gyro-sync-wrapper').show();
$('#gyro-frequency-wrapper').hide();
$('#accelerometer-frequency-wrapper').hide();
$('#attitude-frequency-wrapper').hide();
} else if (INAV_PID_CONFIG.asynchronousMode == 1) {
$('#gyro-sync-wrapper').hide();
$('#gyro-frequency-wrapper').show();
$('#accelerometer-frequency-wrapper').hide();
$('#attitude-frequency-wrapper').hide();
ADVANCED_CONFIG.gyroSync = 1;
} else {
$('#gyro-sync-wrapper').hide();
$('#gyro-frequency-wrapper').show();
$('#accelerometer-frequency-wrapper').show();
$('#attitude-frequency-wrapper').show();
ADVANCED_CONFIG.gyroSync = 1;
} }
} });
$asyncMode.change();
fillSelect($accelerometerFrequency, FC.getAccelerometerTaskFrequencies(), INAV_PID_CONFIG.accelerometerTaskFrequency, 'Hz');
$accelerometerFrequency.val(INAV_PID_CONFIG.accelerometerTaskFrequency);
$accelerometerFrequency.change(function () {
INAV_PID_CONFIG.accelerometerTaskFrequency = $accelerometerFrequency.val();
});
fillSelect($attitudeFrequency, FC.getAttitudeTaskFrequencies(), INAV_PID_CONFIG.attitudeTaskFrequency, 'Hz');
$attitudeFrequency.val(INAV_PID_CONFIG.attitudeTaskFrequency);
$attitudeFrequency.change(function () {
INAV_PID_CONFIG.attitudeTaskFrequency = $attitudeFrequency.val();
});
} else {
fillSelect($looptime, FC.getLooptimes()[125].looptimes, FC_CONFIG.loopTime, 'Hz');
$looptime.val(FC_CONFIG.loopTime); $looptime.val(FC_CONFIG.loopTime);
$looptime.change(function () { $looptime.change(function () {
FC_CONFIG.loopTime = $(this).val(); FC_CONFIG.loopTime = $(this).val();
@ -587,18 +497,14 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
$(".requires-v1_4").hide(); $(".requires-v1_4").hide();
} }
//fill 3D
if (semver.lt(CONFIG.apiVersion, "1.14.0")) { $('input[name="3ddeadbandlow"]').val(_3D.deadband3d_low);
$('.tab-configuration .3d').hide(); $('input[name="3ddeadbandhigh"]').val(_3D.deadband3d_high);
$('input[name="3dneutral"]').val(_3D.neutral3d);
if (semver.lt(CONFIG.apiVersion, "1.17.0")) {
$('input[name="3ddeadbandthrottle"]').val(_3D.deadband3d_throttle);
} else { } else {
$('input[name="3ddeadbandlow"]').val(_3D.deadband3d_low); $('.3ddeadbandthrottle').hide();
$('input[name="3ddeadbandhigh"]').val(_3D.deadband3d_high);
$('input[name="3dneutral"]').val(_3D.neutral3d);
if (semver.lt(CONFIG.apiVersion, "1.17.0")) {
$('input[name="3ddeadbandthrottle"]').val(_3D.deadband3d_throttle);
} else {
$('.3ddeadbandthrottle').hide();
}
} }
$('input[type="checkbox"].feature', features_e).change(function () { $('input[type="checkbox"].feature', features_e).change(function () {
@ -647,11 +553,8 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
MISC.mag_declination = parseFloat($('input[name="mag_declination"]').val()); MISC.mag_declination = parseFloat($('input[name="mag_declination"]').val());
// motor disarm ARMING_CONFIG.auto_disarm_delay = parseInt($('input[name="autodisarmdelay"]').val());
if(semver.gte(CONFIG.apiVersion, "1.8.0")) { ARMING_CONFIG.disarm_kill_switch = ~~$('input[name="disarmkillswitch"]').is(':checked'); // ~~ boolean to decimal conversion
ARMING_CONFIG.auto_disarm_delay = parseInt($('input[name="autodisarmdelay"]').val());
ARMING_CONFIG.disarm_kill_switch = ~~$('input[name="disarmkillswitch"]').is(':checked'); // ~~ boolean to decimal conversion
}
MISC.minthrottle = parseInt($('input[name="minthrottle"]').val()); MISC.minthrottle = parseInt($('input[name="minthrottle"]').val());
MISC.midrc = parseInt($('input[name="midthrottle"]').val()); MISC.midrc = parseInt($('input[name="midthrottle"]').val());
@ -681,12 +584,12 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
// track feature usage // track feature usage
if (FC.isFeatureEnabled('RX_SERIAL', features)) { if (FC.isFeatureEnabled('RX_SERIAL', features)) {
googleAnalytics.sendEvent('Setting', 'SerialRxProvider', serialRXtypes[RX_CONFIG.serialrx_provider]); googleAnalytics.sendEvent('Setting', 'SerialRxProvider', serialRxTypes[RX_CONFIG.serialrx_provider]);
} }
// track feature usage // track feature usage
if (FC.isFeatureEnabled('RX_NRF24', features)) { if (FC.isFeatureEnabled('RX_NRF24', features)) {
googleAnalytics.sendEvent('Setting', 'nrf24Protocol', nrf24Protocoltypes[RX_CONFIG.nrf24rx_protocol]); googleAnalytics.sendEvent('Setting', 'nrf24Protocol', nrf24ProtocolTypes[RX_CONFIG.nrf24rx_protocol]);
} }
if (FC.isFeatureEnabled('GPS', features)) { if (FC.isFeatureEnabled('GPS', features)) {
@ -705,40 +608,20 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
} }
} }
function save_serial_config() {
if (semver.lt(CONFIG.apiVersion, "1.6.0")) {
MSP.send_message(MSPCodes.MSP_SET_CF_SERIAL_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_CF_SERIAL_CONFIG), false, save_misc);
} else {
save_misc();
}
}
function save_misc() { function save_misc() {
MSP.send_message(MSPCodes.MSP_SET_MISC, mspHelper.crunch(MSPCodes.MSP_SET_MISC), false, save_3d); MSP.send_message(MSPCodes.MSP_SET_MISC, mspHelper.crunch(MSPCodes.MSP_SET_MISC), false, save_3d);
} }
function save_3d() { function save_3d() {
var next_callback = save_sensor_alignment; MSP.send_message(MSPCodes.MSP_SET_3D, mspHelper.crunch(MSPCodes.MSP_SET_3D), false, save_sensor_alignment);
if(semver.gte(CONFIG.apiVersion, "1.14.0")) {
MSP.send_message(MSPCodes.MSP_SET_3D, mspHelper.crunch(MSPCodes.MSP_SET_3D), false, next_callback);
} else {
next_callback();
}
} }
function save_sensor_alignment() { function save_sensor_alignment() {
var next_callback = save_acc_trim; MSP.send_message(MSPCodes.MSP_SET_SENSOR_ALIGNMENT, mspHelper.crunch(MSPCodes.MSP_SET_SENSOR_ALIGNMENT), false, save_acc_trim);
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);
} 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 MSP.send_message(MSPCodes.MSP_SET_ACC_TRIM, mspHelper.crunch(MSPCodes.MSP_SET_ACC_TRIM), false, save_arming_config);
, semver.gte(CONFIG.apiVersion, "1.8.0") ? save_arming_config : save_to_eeprom);
} }
function save_arming_config() { function save_arming_config() {
@ -781,6 +664,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
} }
function reboot() { function reboot() {
//noinspection JSUnresolvedVariable
GUI.log(chrome.i18n.getMessage('configurationEepromSaved')); GUI.log(chrome.i18n.getMessage('configurationEepromSaved'));
GUI.tab_switch_cleanup(function() { GUI.tab_switch_cleanup(function() {
@ -789,6 +673,7 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
} }
function reinitialize() { function reinitialize() {
//noinspection JSUnresolvedVariable
GUI.log(chrome.i18n.getMessage('deviceRebooting')); GUI.log(chrome.i18n.getMessage('deviceRebooting'));
if (BOARD.find_board_definition(CONFIG.boardIdentifier).vcp) { // VCP-based flight controls may crash old drivers, we catch and reconnect if (BOARD.find_board_definition(CONFIG.boardIdentifier).vcp) { // VCP-based flight controls may crash old drivers, we catch and reconnect
@ -800,19 +685,25 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() { GUI.timeout_add('waiting_for_bootup', function waiting_for_bootup() {
MSP.send_message(MSPCodes.MSP_IDENT, false, false, function () { MSP.send_message(MSPCodes.MSP_IDENT, false, false, function () {
//noinspection JSUnresolvedVariable
GUI.log(chrome.i18n.getMessage('deviceReady')); GUI.log(chrome.i18n.getMessage('deviceReady'));
//noinspection JSValidateTypes
TABS.configuration.initialize(false, $('#content').scrollTop()); TABS.configuration.initialize(false, $('#content').scrollTop());
}); });
},1500); // 1500 ms seems to be just the right amount of delay to prevent data request timeouts },1500); // 1500 ms seems to be just the right amount of delay to prevent data request timeouts
} }
} }
MSP.send_message(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG), false, save_serial_config); MSP.send_message(MSPCodes.MSP_SET_BF_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_BF_CONFIG), false, save_misc);
}); });
// status data pulled via separate timer with static speed // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function status_pull() { GUI.interval_add('status_pull', function status_pull() {
MSP.send_message(MSPCodes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
MSP.send_message(MSPCodes.MSP_SENSOR_STATUS);
}
}, 250, true); }, 250, true);
GUI.interval_add('config_load_analog', load_analog, 250, true); // 4 fps GUI.interval_add('config_load_analog', load_analog, 250, true); // 4 fps
GUI.content_ready(callback); GUI.content_ready(callback);

View file

@ -375,6 +375,10 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
// status data pulled via separate timer with static speed // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function status_pull() { GUI.interval_add('status_pull', function status_pull() {
MSP.send_message(MSPCodes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
MSP.send_message(MSPCodes.MSP_SENSOR_STATUS);
}
}, 250, true); }, 250, true);
GUI.content_ready(callback); GUI.content_ready(callback);

View file

@ -114,6 +114,10 @@ TABS.gps.initialize = function (callback) {
// status data pulled via separate timer with static speed // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function status_pull() { GUI.interval_add('status_pull', function status_pull() {
MSP.send_message(MSPCodes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
MSP.send_message(MSPCodes.MSP_SENSOR_STATUS);
}
}, 250, true); }, 250, true);

View file

@ -147,6 +147,10 @@ TABS.modes.initialize = function (callback) {
// status data pulled via separate timer with static speed // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function status_pull() { GUI.interval_add('status_pull', function status_pull() {
MSP.send_message(MSPCodes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
MSP.send_message(MSPCodes.MSP_SENSOR_STATUS);
}
}, 250, true); }, 250, true);
GUI.content_ready(callback); GUI.content_ready(callback);

View file

@ -456,6 +456,15 @@ TABS.motors.initialize = function (callback) {
function get_status() { function get_status() {
// status needed for arming flag // status needed for arming flag
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
MSP.send_message(MSPCodes.MSP_STATUS, false, false, get_sensor_status);
}
else {
MSP.send_message(MSPCodes.MSP_STATUS, false, false, get_motor_data);
}
}
function get_sensor_status() {
MSP.send_message(MSPCodes.MSP_STATUS, false, false, get_motor_data); MSP.send_message(MSPCodes.MSP_STATUS, false, false, get_motor_data);
} }

View file

@ -222,6 +222,10 @@ TABS.ports.initialize = function (callback, scrollPosition) {
// status data pulled via separate timer with static speed // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function status_pull() { GUI.interval_add('status_pull', function status_pull() {
MSP.send_message(MSPCodes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
MSP.send_message(MSPCodes.MSP_SENSOR_STATUS);
}
}, 250, true); }, 250, true);
GUI.content_ready(callback); GUI.content_ready(callback);

View file

@ -486,6 +486,10 @@ TABS.receiver.initialize = function (callback) {
// status data pulled via separate timer with static speed // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function status_pull() { GUI.interval_add('status_pull', function status_pull() {
MSP.send_message(MSPCodes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
MSP.send_message(MSPCodes.MSP_SENSOR_STATUS);
}
}, 250, true); }, 250, true);
GUI.content_ready(callback); GUI.content_ready(callback);

View file

@ -446,6 +446,10 @@ TABS.sensors.initialize = function (callback) {
// status data pulled via separate timer with static speed // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function status_pull() { GUI.interval_add('status_pull', function status_pull() {
MSP.send_message(MSPCodes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
MSP.send_message(MSPCodes.MSP_SENSOR_STATUS);
}
}, 250, true); }, 250, true);
GUI.content_ready(callback); GUI.content_ready(callback);

View file

@ -191,6 +191,10 @@ TABS.servos.initialize = function (callback) {
// status data pulled via separate timer with static speed // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function () { GUI.interval_add('status_pull', function () {
MSP.send_message(MSPCodes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
MSP.send_message(MSPCodes.MSP_SENSOR_STATUS);
}
}, 250, true); }, 250, true);
GUI.content_ready(callback); GUI.content_ready(callback);

View file

@ -67,9 +67,9 @@
height: 100%; height: 100%;
top: 0; top: 0;
left: 0; left: 0;
background-size: 100%;
background: url(../images/paper.jpg) center; background: url(../images/paper.jpg) center;
border-radius: 5px; border-radius: 5px;
background-size: contain;
} }
#canvas { #canvas {

View file

@ -172,6 +172,10 @@ TABS.setup.initialize = function (callback) {
function get_slow_data() { function get_slow_data() {
MSP.send_message(MSPCodes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
MSP.send_message(MSPCodes.MSP_SENSOR_STATUS);
}
MSP.send_message(MSPCodes.MSP_ANALOG, false, false, function () { MSP.send_message(MSPCodes.MSP_ANALOG, false, false, function () {
bat_voltage_e.text(chrome.i18n.getMessage('initialSetupBatteryValue', [ANALOG.voltage])); bat_voltage_e.text(chrome.i18n.getMessage('initialSetupBatteryValue', [ANALOG.voltage]));
bat_mah_drawn_e.text(chrome.i18n.getMessage('initialSetupBatteryMahValue', [ANALOG.mAhdrawn])); bat_mah_drawn_e.text(chrome.i18n.getMessage('initialSetupBatteryMahValue', [ANALOG.mAhdrawn]));

View file

@ -94,6 +94,10 @@ TABS.transponder.initialize = function (callback, scrollPosition) {
// status data pulled via separate timer with static speed // status data pulled via separate timer with static speed
GUI.interval_add('status_pull', function status_pull() { GUI.interval_add('status_pull', function status_pull() {
MSP.send_message(MSPCodes.MSP_STATUS); MSP.send_message(MSPCodes.MSP_STATUS);
if (semver.gte(CONFIG.flightControllerVersion, "1.5.0")) {
MSP.send_message(MSPCodes.MSP_SENSOR_STATUS);
}
}, 250, true); }, 250, true);
GUI.content_ready(callback); GUI.content_ready(callback);