1
0
Fork 0
mirror of https://github.com/iNavFlight/inav-configurator.git synced 2025-07-17 13:25:22 +03:00

1.6 is gone

This commit is contained in:
Pawel Spychalski (DzikuVx) 2019-01-15 17:50:23 +01:00
parent 0958b45dad
commit 529c40e556
8 changed files with 37 additions and 187 deletions

View file

@ -557,27 +557,10 @@ var FC = {
); );
} }
if (semver.lt(CONFIG.flightControllerVersion, "1.6.0")) {
features.push(
{bit: 2, group: 'other', name: 'INFLIGHT_ACC_CAL', showNameInTip: true},
{bit: 9, group: 'other', name: 'SONAR', showNameInTip: true},
{bit: 8, group: 'rxFailsafe', name: 'FAILSAFE'}
);
}
features.push( features.push(
{bit: 28, group: 'esc-priority', name: 'PWM_OUTPUT_ENABLE', haveTip: true} {bit: 28, group: 'esc-priority', name: 'PWM_OUTPUT_ENABLE', haveTip: true}
); );
/*
* Transponder disabled until not implemented in firmware
*/
if (false && semver.gte(CONFIG.apiVersion, "1.16.0")) {
features.push(
{bit: 21, group: 'other', name: 'TRANSPONDER', haveTip: true, showNameInTip: true}
);
}
if (semver.gte(CONFIG.apiVersion, "1.21.0")) { if (semver.gte(CONFIG.apiVersion, "1.21.0")) {
features.push( features.push(
{bit: 26, group: 'other', name: 'SOFTSPI'} {bit: 26, group: 'other', name: 'SOFTSPI'}
@ -833,14 +816,11 @@ var FC = {
'SUMH', 'SUMH',
'XBUS_MODE_B', 'XBUS_MODE_B',
'XBUS_MODE_B_RJ01', 'XBUS_MODE_B_RJ01',
'IBUS' 'IBUS',
'JETI EXBUS',
'TBS Crossfire'
]; ];
if (semver.gte(CONFIG.flightControllerVersion, "1.6.0")) {
data.push('JETI EXBUS');
data.push('TBS Crossfire');
}
if (semver.gte(CONFIG.flightControllerVersion, "1.9.1")) { if (semver.gte(CONFIG.flightControllerVersion, "1.9.1")) {
data.push('FPort'); data.push('FPort');
} }
@ -1072,23 +1052,18 @@ var FC = {
] ]
}, },
getPidNames: function () { getPidNames: function () {
return [
if (semver.lt(CONFIG.flightControllerVersion, "1.6.0")) { 'Roll',
return PID_names; 'Pitch',
} else { 'Yaw',
return [ 'Position Z',
'Roll', 'Position XY',
'Pitch', 'Velocity XY',
'Yaw', 'Surface',
'Position Z', 'Level',
'Position XY', 'Heading',
'Velocity XY', 'Velocity Z'
'Surface', ];
'Level',
'Heading',
'Velocity Z'
];
}
}, },
getRthAltControlMode: function () { getRthAltControlMode: function () {
return ["Current", "Extra", "Fixed", "Max", "At Least"]; return ["Current", "Extra", "Fixed", "Max", "At Least"];

View file

@ -216,10 +216,7 @@ var mspHelper = (function (gui) {
break; break;
case MSPCodes.MSP_ALTITUDE: case MSPCodes.MSP_ALTITUDE:
SENSOR_DATA.altitude = parseFloat((data.getInt32(0, true) / 100.0).toFixed(2)); // correct scale factor SENSOR_DATA.altitude = parseFloat((data.getInt32(0, true) / 100.0).toFixed(2)); // correct scale factor
// On 1.6 and above this provides also baro raw altitude SENSOR_DATA.barometer = parseFloat((data.getInt32(6, true) / 100.0).toFixed(2)); // correct scale factor
if (semver.gte(CONFIG.flightControllerVersion, "1.6.0")) {
SENSOR_DATA.barometer = parseFloat((data.getInt32(6, true) / 100.0).toFixed(2)); // correct scale factor
}
break; break;
case MSPCodes.MSP_SONAR: case MSPCodes.MSP_SONAR:
SENSOR_DATA.sonar = data.getInt32(0, true); SENSOR_DATA.sonar = data.getInt32(0, true);
@ -1177,12 +1174,8 @@ var mspHelper = (function (gui) {
PID_ADVANCED.rollPitchItermIgnoreRate = data.getUint16(0, true); PID_ADVANCED.rollPitchItermIgnoreRate = data.getUint16(0, true);
PID_ADVANCED.yawItermIgnoreRate = data.getUint16(2, true); PID_ADVANCED.yawItermIgnoreRate = data.getUint16(2, true);
PID_ADVANCED.yawPLimit = data.getUint16(4, true); PID_ADVANCED.yawPLimit = data.getUint16(4, true);
PID_ADVANCED.dtermSetpointWeight = data.getUint8(9);
if (semver.gte(CONFIG.flightControllerVersion, "1.6.0")) { PID_ADVANCED.pidSumLimit = data.getUint16(10, true);
PID_ADVANCED.dtermSetpointWeight = data.getUint8(9);
PID_ADVANCED.pidSumLimit = data.getUint16(10, true);
}
PID_ADVANCED.axisAccelerationLimitRollPitch = data.getUint16(13, true); PID_ADVANCED.axisAccelerationLimitRollPitch = data.getUint16(13, true);
PID_ADVANCED.axisAccelerationLimitYaw = data.getUint16(15, true); PID_ADVANCED.axisAccelerationLimitYaw = data.getUint16(15, true);
break; break;
@ -2016,15 +2009,9 @@ var mspHelper = (function (gui) {
buffer.push(0); //BF: currentProfile->pidProfile.vbatPidCompensation buffer.push(0); //BF: currentProfile->pidProfile.vbatPidCompensation
buffer.push(0); //BF: currentProfile->pidProfile.setpointRelaxRatio buffer.push(0); //BF: currentProfile->pidProfile.setpointRelaxRatio
if (semver.gte(CONFIG.flightControllerVersion, "1.6.0")) { buffer.push(PID_ADVANCED.dtermSetpointWeight);
buffer.push(PID_ADVANCED.dtermSetpointWeight); buffer.push(lowByte(PID_ADVANCED.pidSumLimit));
buffer.push(lowByte(PID_ADVANCED.pidSumLimit)); buffer.push(highByte(PID_ADVANCED.pidSumLimit));
buffer.push(highByte(PID_ADVANCED.pidSumLimit));
} else {
buffer.push(0);
buffer.push(0); // reserved
buffer.push(0); // reserved
}
buffer.push(0); //BF: currentProfile->pidProfile.itermThrottleGain buffer.push(0); //BF: currentProfile->pidProfile.itermThrottleGain
@ -2837,35 +2824,19 @@ var mspHelper = (function (gui) {
}; };
self.loadNavPosholdConfig = function (callback) { self.loadNavPosholdConfig = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, "1.6.0")) { MSP.send_message(MSPCodes.MSP_NAV_POSHOLD, false, false, callback);
MSP.send_message(MSPCodes.MSP_NAV_POSHOLD, false, false, callback);
} else {
callback();
}
}; };
self.saveNavPosholdConfig = function (callback) { self.saveNavPosholdConfig = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, "1.6.0")) { MSP.send_message(MSPCodes.MSP_SET_NAV_POSHOLD, mspHelper.crunch(MSPCodes.MSP_SET_NAV_POSHOLD), false, callback);
MSP.send_message(MSPCodes.MSP_SET_NAV_POSHOLD, mspHelper.crunch(MSPCodes.MSP_SET_NAV_POSHOLD), false, callback);
} else {
callback();
}
}; };
self.loadPositionEstimationConfig = function (callback) { self.loadPositionEstimationConfig = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, "1.6.0")) { MSP.send_message(MSPCodes.MSP_POSITION_ESTIMATION_CONFIG, false, false, callback);
MSP.send_message(MSPCodes.MSP_POSITION_ESTIMATION_CONFIG, false, false, callback);
} else {
callback();
}
}; };
self.savePositionEstimationConfig = function (callback) { self.savePositionEstimationConfig = function (callback) {
if (semver.gte(CONFIG.flightControllerVersion, "1.6.0")) { MSP.send_message(MSPCodes.MSP_SET_POSITION_ESTIMATION_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_POSITION_ESTIMATION_CONFIG), false, callback);
MSP.send_message(MSPCodes.MSP_SET_POSITION_ESTIMATION_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_POSITION_ESTIMATION_CONFIG), false, callback);
} else {
callback();
}
}; };
self.loadCalibrationData = function (callback) { self.loadCalibrationData = function (callback) {

View file

@ -4,11 +4,6 @@
<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 pre-v1_6">
<div class="note_spacer">
<p data-i18n="failsafeFeaturesHelpNew"></p>
</div>
</div>
<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">
@ -28,17 +23,6 @@
</div> </div>
</div> </div>
</div> </div>
<div class="gui_box grey stage1 pre-v1_6">
<div class="gui_box_titlebar">
<div class="spacer_box_title" data-i18n="failsafeChannelFallbackSettingsTitle"></div>
<div class="helpicon cf_tip" data-i18n_title="failsafeChannelFallbackSettingsHelp"></div>
</div>
<div class="spacer_box">
<div class="activechannellist">
<!-- list generated here -->
</div>
</div>
</div>
</div> </div>
<div class="rightWrapper"> <div class="rightWrapper">
<div class="gui_box grey"> <div class="gui_box grey">
@ -46,14 +30,6 @@
<div class="spacer_box_title" data-i18n="failsafeStageTwoSettingsTitle"></div> <div class="spacer_box_title" data-i18n="failsafeStageTwoSettingsTitle"></div>
</div> </div>
<div class="spacer_box"> <div class="spacer_box">
<div class="checkbox pre-v1_6">
<div class="numberspacer" >
<input type="checkbox" name="failsafe_feature_new" class="feature toggle rxFailsafe" id="failsafe_feature_new" />
</div>
<label for="failsafe_feature_new"><span data-i18n="failsafeFeatureItem"></span>
</label>
<div class="helpicon cf_tip" data-i18n_title="failsafeFeatureHelp"></div>
</div>
<div class="checkbox stage2"> <div class="checkbox stage2">
<div class="numberspacer" > <div class="numberspacer" >
<input type="checkbox" name="failsafe_kill_switch" class="toggle" id="failsafe_kill_switch" /> <input type="checkbox" name="failsafe_kill_switch" class="toggle" id="failsafe_kill_switch" />
@ -98,7 +74,7 @@
<label for="rth" data-i18n="failsafeProcedureItemSelect3"></label> <label for="rth" data-i18n="failsafeProcedureItemSelect3"></label>
</div> </div>
</div> </div>
<div class="radioarea pro5 stage2 requires-v1_6"> <div class="radioarea pro5 stage2">
<div class="radiobuttons"><input class="procedure" id="nothing" name="group1" type="radio"/> <div class="radiobuttons"><input class="procedure" id="nothing" name="group1" type="radio"/>
<label for="nothing" data-i18n="failsafeProcedureItemSelect4"></label> <label for="nothing" data-i18n="failsafeProcedureItemSelect4"></label>
</div> </div>

View file

@ -14,31 +14,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
} }
function load_failssafe_config() { function load_failssafe_config() {
MSP.send_message(MSPCodes.MSP_FAILSAFE_CONFIG, false, false, load_rxfail_config); MSP.send_message(MSPCodes.MSP_FAILSAFE_CONFIG, false, false, get_box_ids);
}
function load_rxfail_config() {
if (semver.lt(CONFIG.flightControllerVersion, "1.6.0")) {
MSP.send_message(MSPCodes.MSP_RXFAIL_CONFIG, false, false, get_box_names);
} else {
get_box_names();
}
}
function get_box_names() {
if (semver.lt(CONFIG.flightControllerVersion, "1.6.0")) {
MSP.send_message(MSPCodes.MSP_BOXNAMES, false, false, get_mode_ranges);
} else {
get_mode_ranges();
}
}
function get_mode_ranges() {
if (semver.lt(CONFIG.flightControllerVersion, "1.6.0")) {
MSP.send_message(MSPCodes.MSP_MODE_RANGES, false, false, get_box_ids);
} else {
get_box_ids();
}
} }
function get_box_ids() { function get_box_ids() {
@ -65,11 +41,6 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
function process_html() { function process_html() {
if (semver.gte(CONFIG.flightControllerVersion, "1.6.0")) {
$('.pre-v1_6').hide();
$('.requires-v1_6').show();
}
var failsafeFeature; var failsafeFeature;
// translate to user-selected language // translate to user-selected language
@ -206,13 +177,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
channel_mode_array[i].change(); channel_mode_array[i].change();
} }
var isFailsafeEnabled; var isFailsafeEnabled = true;
if (semver.gte(CONFIG.flightControllerVersion, "1.6.0")) {
isFailsafeEnabled = true;
} else {
isFailsafeEnabled = bit_check(BF_CONFIG.features, 8);
}
// fill stage 2 fields // fill stage 2 fields
failsafeFeature = $('input[name="failsafe_feature_new"]'); failsafeFeature = $('input[name="failsafe_feature_new"]');
@ -327,14 +292,6 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
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());
if (semver.lt(CONFIG.flightControllerVersion, "1.6.0")) {
if ($('input[name="failsafe_feature_new"]').is(':checked')) {
BF_CONFIG.features = bit_set(BF_CONFIG.features, 8);
} else {
BF_CONFIG.features = bit_clear(BF_CONFIG.features, 8);
}
}
FAILSAFE_CONFIG.failsafe_throttle = parseInt($('input[name="failsafe_throttle"]').val()); FAILSAFE_CONFIG.failsafe_throttle = parseInt($('input[name="failsafe_throttle"]').val());
FAILSAFE_CONFIG.failsafe_off_delay = parseInt($('input[name="failsafe_off_delay"]').val()); FAILSAFE_CONFIG.failsafe_off_delay = parseInt($('input[name="failsafe_off_delay"]').val());
FAILSAFE_CONFIG.failsafe_throttle_low_delay = parseInt($('input[name="failsafe_throttle_low_delay"]').val()); FAILSAFE_CONFIG.failsafe_throttle_low_delay = parseInt($('input[name="failsafe_throttle_low_delay"]').val());
@ -356,15 +313,7 @@ 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;
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_bf_config);
}
function save_rxfail_config() {
if (semver.lt(CONFIG.flightControllerVersion, "1.6.0")) {
mspHelper.sendRxFailConfig(save_bf_config);
} else {
save_bf_config();
}
} }
function save_bf_config() { function save_bf_config() {

View file

@ -586,7 +586,6 @@ OSD.constants = {
{ {
name: 'HEADING', name: 'HEADING',
id: 24, id: 24,
min_version: '1.6.0',
preview: FONT.symbol(SYM.HEADING) + '175' + FONT.symbol(SYM.DEGREES) preview: FONT.symbol(SYM.HEADING) + '175' + FONT.symbol(SYM.DEGREES)
}, },
{ {
@ -663,7 +662,6 @@ OSD.constants = {
{ {
name: 'VARIO', name: 'VARIO',
id: 25, id: 25,
min_version: '1.6.0',
preview: FONT.symbol(SYM.VARIO_UP_2A) + '\n' + preview: FONT.symbol(SYM.VARIO_UP_2A) + '\n' +
FONT.symbol(SYM.VARIO_UP_2A) + '\n' + FONT.symbol(SYM.VARIO_UP_2A) + '\n' +
FONT.symbol(SYM.VARIO_UP_2A) + '\n' + FONT.symbol(SYM.VARIO_UP_2A) + '\n' +
@ -673,7 +671,6 @@ OSD.constants = {
{ {
name: 'VARIO_NUM', name: 'VARIO_NUM',
id: 26, id: 26,
min_version: '1.6.0',
preview: function(osd_data) { preview: function(osd_data) {
if (OSD.data.preferences.units === 0) { if (OSD.data.preferences.units === 0) {
// Imperial // Imperial
@ -766,7 +763,6 @@ OSD.constants = {
{ {
name: 'POWER', name: 'POWER',
id: 19, id: 19,
min_version: '1.6.0',
preview: FONT.symbol(SYM.WATT) + '50 ' // 3 chars preview: FONT.symbol(SYM.WATT) + '50 ' // 3 chars
}, },
{ {
@ -839,13 +835,11 @@ OSD.constants = {
{ {
name: 'LONGITUDE', name: 'LONGITUDE',
id: 20, id: 20,
min_version: '1.6.0',
preview: osdCoordinatePreview(SYM.LON, -114.7652134), preview: osdCoordinatePreview(SYM.LON, -114.7652134),
}, },
{ {
name: 'LATITUDE', name: 'LATITUDE',
id: 21, id: 21,
min_version: '1.6.0',
preview: osdCoordinatePreview(SYM.LAT, 52.9872367), preview: osdCoordinatePreview(SYM.LAT, 52.9872367),
}, },
{ {
@ -861,7 +855,6 @@ OSD.constants = {
{ {
name: 'DIRECTION_TO_HOME', name: 'DIRECTION_TO_HOME',
id: 22, id: 22,
min_version: '1.6.0',
preview: FONT.symbol(SYM.DIR_TO_HOME) preview: FONT.symbol(SYM.DIR_TO_HOME)
}, },
{ {
@ -873,7 +866,6 @@ OSD.constants = {
{ {
name: 'DISTANCE_TO_HOME', name: 'DISTANCE_TO_HOME',
id: 23, id: 23,
min_version: '1.6.0',
preview: function(osd_data) { preview: function(osd_data) {
if (OSD.data.preferences.units === 0) { if (OSD.data.preferences.units === 0) {
// Imperial // Imperial
@ -988,7 +980,6 @@ OSD.constants = {
}, },
{ {
name: 'osdGroupPIDs', name: 'osdGroupPIDs',
min_version: '1.6.0',
items: [ items: [
{ {
name: 'ROLL_PIDS', name: 'ROLL_PIDS',

View file

@ -238,28 +238,28 @@
</td> </td>
</tr> </tr>
<tr class="requires-v1_6"> <tr>
<th data-i18n="gyroNotchHz1"></th> <th data-i18n="gyroNotchHz1"></th>
<td> <td>
<input type="number" data-simple-bind="FILTER_CONFIG.gyroNotchHz1" id="gyroNotchHz1" class="rate-tpa_input" step="1" min="0" max="500" /> Hz <input type="number" data-simple-bind="FILTER_CONFIG.gyroNotchHz1" id="gyroNotchHz1" class="rate-tpa_input" step="1" min="0" max="500" /> Hz
<div class="helpicon cf_tip" data-i18n_title="gyroNotchHz1Help"></div> <div class="helpicon cf_tip" data-i18n_title="gyroNotchHz1Help"></div>
</td> </td>
</tr> </tr>
<tr class="requires-v1_6"> <tr>
<th data-i18n="gyroNotchCutoff1"></th> <th data-i18n="gyroNotchCutoff1"></th>
<td> <td>
<input type="number" data-simple-bind="FILTER_CONFIG.gyroNotchCutoff1" id="gyroNotchCutoff1" class="rate-tpa_input" step="1" min="0" max="500" /> Hz <input type="number" data-simple-bind="FILTER_CONFIG.gyroNotchCutoff1" id="gyroNotchCutoff1" class="rate-tpa_input" step="1" min="0" max="500" /> Hz
<div class="helpicon cf_tip" data-i18n_title="gyroNotchCutoff1Help"></div> <div class="helpicon cf_tip" data-i18n_title="gyroNotchCutoff1Help"></div>
</td> </td>
</tr> </tr>
<tr class="requires-v1_6"> <tr>
<th data-i18n="gyroNotchHz2"></th> <th data-i18n="gyroNotchHz2"></th>
<td> <td>
<input type="number" data-simple-bind="FILTER_CONFIG.gyroNotchHz2" id="gyroNotchHz2" class="rate-tpa_input" step="1" min="0" max="500" /> Hz <input type="number" data-simple-bind="FILTER_CONFIG.gyroNotchHz2" id="gyroNotchHz2" class="rate-tpa_input" step="1" min="0" max="500" /> Hz
<div class="helpicon cf_tip" data-i18n_title="gyroNotchHz2Help"></div> <div class="helpicon cf_tip" data-i18n_title="gyroNotchHz2Help"></div>
</td> </td>
</tr> </tr>
<tr class="requires-v1_6"> <tr>
<th data-i18n="gyroNotchCutoff2"></th> <th data-i18n="gyroNotchCutoff2"></th>
<td> <td>
<input type="number" data-simple-bind="FILTER_CONFIG.gyroNotchCutoff2" id="gyroNotchCutoff2" class="rate-tpa_input" step="1" min="0" max="500" /> Hz <input type="number" data-simple-bind="FILTER_CONFIG.gyroNotchCutoff2" id="gyroNotchCutoff2" class="rate-tpa_input" step="1" min="0" max="500" /> Hz
@ -287,14 +287,14 @@
<div class="helpicon cf_tip" data-i18n_title="yawLpfCutoffFrequencyHelp"></div> <div class="helpicon cf_tip" data-i18n_title="yawLpfCutoffFrequencyHelp"></div>
</td> </td>
</tr> </tr>
<tr class="requires-v1_6"> <tr>
<th data-i18n="dtermNotchHz"></th> <th data-i18n="dtermNotchHz"></th>
<td> <td>
<input type="number" data-simple-bind="FILTER_CONFIG.dtermNotchHz" id="dtermNotchHz" class="rate-tpa_input" step="1" min="0" max="500" /> Hz <input type="number" data-simple-bind="FILTER_CONFIG.dtermNotchHz" id="dtermNotchHz" class="rate-tpa_input" step="1" min="0" max="500" /> Hz
<div class="helpicon cf_tip" data-i18n_title="dtermNotchHzHelp"></div> <div class="helpicon cf_tip" data-i18n_title="dtermNotchHzHelp"></div>
</td> </td>
</tr> </tr>
<tr class="requires-v1_6"> <tr>
<th data-i18n="dtermNotchCutoff"></th> <th data-i18n="dtermNotchCutoff"></th>
<td> <td>
<input type="number" data-simple-bind="FILTER_CONFIG.dtermNotchCutoff" id="dtermNotchCutoff" class="rate-tpa_input" step="1" min="0" max="500" /> Hz <input type="number" data-simple-bind="FILTER_CONFIG.dtermNotchCutoff" id="dtermNotchCutoff" class="rate-tpa_input" step="1" min="0" max="500" /> Hz

View file

@ -201,12 +201,6 @@ TABS.pid_tuning.initialize = function (callback) {
PID_ADVANCED.axisAccelerationLimitYaw = Math.round(parseInt($axisAccelerationLimitYaw.val(), 10) / 10); PID_ADVANCED.axisAccelerationLimitYaw = Math.round(parseInt($axisAccelerationLimitYaw.val(), 10) / 10);
}); });
if (semver.gte(CONFIG.flightControllerVersion, "1.6.0")) {
$('.requires-v1_6').show();
} else {
$('.requires-v1_6').hide();
}
if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) { if (semver.gte(CONFIG.flightControllerVersion, "2.0.0")) {
$('.deprecated-v2_0').hide(); $('.deprecated-v2_0').hide();
} else { } else {

View file

@ -269,7 +269,7 @@ TABS.sensors.initialize = function (callback) {
gyro_data = initDataArray(3), gyro_data = initDataArray(3),
accel_data = initDataArray(3), accel_data = initDataArray(3),
mag_data = initDataArray(3), mag_data = initDataArray(3),
altitude_data = (semver.gte(CONFIG.flightControllerVersion, "1.6.0")) ? initDataArray(2) : initDataArray(1), altitude_data = initDataArray(2),
sonar_data = initDataArray(1), sonar_data = initDataArray(1),
airspeed_data = initDataArray(1), airspeed_data = initDataArray(1),
debug_data = [ debug_data = [
@ -499,13 +499,7 @@ TABS.sensors.initialize = function (callback) {
function update_altitude_graph() { function update_altitude_graph() {
updateGraphHelperSize(altitudeHelpers); updateGraphHelperSize(altitudeHelpers);
samples_altitude_i = addSampleToData(altitude_data, samples_altitude_i, [SENSOR_DATA.altitude, SENSOR_DATA.barometer]);
if (semver.gte(CONFIG.flightControllerVersion, "1.6.0")) {
samples_altitude_i = addSampleToData(altitude_data, samples_altitude_i, [SENSOR_DATA.altitude, SENSOR_DATA.barometer]);
}
else {
samples_altitude_i = addSampleToData(altitude_data, samples_altitude_i, [SENSOR_DATA.altitude]);
}
drawGraph(altitudeHelpers, altitude_data, samples_altitude_i); drawGraph(altitudeHelpers, altitude_data, samples_altitude_i);
raw_data_text_ements.x[3].text(SENSOR_DATA.altitude.toFixed(2)); raw_data_text_ements.x[3].text(SENSOR_DATA.altitude.toFixed(2));
raw_data_text_ements.y[3].text(SENSOR_DATA.barometer.toFixed(2)); raw_data_text_ements.y[3].text(SENSOR_DATA.barometer.toFixed(2));