mirror of
https://github.com/iNavFlight/inav-configurator.git
synced 2025-07-15 12:25:13 +03:00
1.7 family removed
This commit is contained in:
parent
bb587d565a
commit
97c622fbb1
11 changed files with 172 additions and 293 deletions
41
js/fc.js
41
js/fc.js
|
@ -576,11 +576,9 @@ var FC = {
|
||||||
{bit: 29, group: 'other', name: 'OSD', haveTip: false, showNameInTip: false}
|
{bit: 29, group: 'other', name: 'OSD', haveTip: false, showNameInTip: false}
|
||||||
);
|
);
|
||||||
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, '1.7.3')) {
|
|
||||||
features.push(
|
features.push(
|
||||||
{bit: 22, group: 'other', name: 'AIRMODE', haveTip: false, showNameInTip: false}
|
{bit: 22, group: 'other', name: 'AIRMODE', haveTip: false, showNameInTip: false}
|
||||||
);
|
);
|
||||||
}
|
|
||||||
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, '1.8.1')) {
|
if (semver.gte(CONFIG.flightControllerVersion, '1.8.1')) {
|
||||||
features.push(
|
features.push(
|
||||||
|
@ -697,22 +695,14 @@ var FC = {
|
||||||
];
|
];
|
||||||
},
|
},
|
||||||
getGpsProtocols: function () {
|
getGpsProtocols: function () {
|
||||||
var data = [
|
return [
|
||||||
'NMEA',
|
'NMEA',
|
||||||
'UBLOX',
|
'UBLOX',
|
||||||
'I2C-NAV',
|
'I2C-NAV',
|
||||||
'DJI NAZA'
|
'DJI NAZA',
|
||||||
|
'UBLOX7',
|
||||||
|
'MTK'
|
||||||
];
|
];
|
||||||
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.7.1")) {
|
|
||||||
data.push('UBLOX7')
|
|
||||||
}
|
|
||||||
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.7.2")) {
|
|
||||||
data.push('MTK')
|
|
||||||
}
|
|
||||||
|
|
||||||
return data;
|
|
||||||
},
|
},
|
||||||
getGpsBaudRates: function () {
|
getGpsBaudRates: function () {
|
||||||
return [
|
return [
|
||||||
|
@ -769,12 +759,10 @@ var FC = {
|
||||||
|
|
||||||
// Versions using feature bits don't allow not having an
|
// Versions using feature bits don't allow not having an
|
||||||
// RX and fallback to RX_PPM.
|
// RX and fallback to RX_PPM.
|
||||||
if (semver.gt(CONFIG.flightControllerVersion, "1.7.3")) {
|
|
||||||
rxTypes.push({
|
rxTypes.push({
|
||||||
name: 'RX_NONE',
|
name: 'RX_NONE',
|
||||||
value: 0,
|
value: 0,
|
||||||
});
|
});
|
||||||
}
|
|
||||||
|
|
||||||
return rxTypes;
|
return rxTypes;
|
||||||
},
|
},
|
||||||
|
@ -788,25 +776,10 @@ var FC = {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (semver.gt(CONFIG.flightControllerVersion, "1.7.3")) {
|
|
||||||
return RX_CONFIG.receiver_type == rxType.value;
|
return RX_CONFIG.receiver_type == rxType.value;
|
||||||
}
|
|
||||||
return bit_check(BF_CONFIG.features, rxType.bit);
|
|
||||||
},
|
},
|
||||||
setRxTypeEnabled: function(rxType) {
|
setRxTypeEnabled: function(rxType) {
|
||||||
if (semver.gt(CONFIG.flightControllerVersion, "1.7.3")) {
|
|
||||||
RX_CONFIG.receiver_type = rxType.value;
|
RX_CONFIG.receiver_type = rxType.value;
|
||||||
} else {
|
|
||||||
// Clear other rx features before
|
|
||||||
var rxTypes = this.getRxTypes();
|
|
||||||
for (var ii = 0; ii < rxTypes.length; ii++) {
|
|
||||||
BF_CONFIG.features = bit_clear(BF_CONFIG.features, rxTypes[ii].bit);
|
|
||||||
}
|
|
||||||
// Set the feature for this rx type (if any, RX_NONE is set by clearing all)
|
|
||||||
if (rxType.bit !== undefined) {
|
|
||||||
BF_CONFIG.features = bit_set(BF_CONFIG.features, rxType.bit);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
},
|
},
|
||||||
getSerialRxTypes: function () {
|
getSerialRxTypes: function () {
|
||||||
var data = [
|
var data = [
|
||||||
|
@ -1070,11 +1043,7 @@ var FC = {
|
||||||
return ["Current", "Extra", "Fixed", "Max", "At Least"];
|
return ["Current", "Extra", "Fixed", "Max", "At Least"];
|
||||||
},
|
},
|
||||||
getRthAllowLanding: function() {
|
getRthAllowLanding: function() {
|
||||||
var values = ["Never", "Always"];
|
return ["Never", "Always", "Only on failsafe"];
|
||||||
if (semver.gt(CONFIG.flightControllerVersion, '1.7.3')) {
|
|
||||||
values.push("Only on failsafe");
|
|
||||||
}
|
|
||||||
return values;
|
|
||||||
},
|
},
|
||||||
getFailsafeProcedure: function () {
|
getFailsafeProcedure: function () {
|
||||||
return {
|
return {
|
||||||
|
|
|
@ -93,12 +93,6 @@ var mspHelper = (function (gui) {
|
||||||
CONFIG.cycleTime = data.getUint16(0, true);
|
CONFIG.cycleTime = data.getUint16(0, true);
|
||||||
CONFIG.i2cError = data.getUint16(2, true);
|
CONFIG.i2cError = data.getUint16(2, true);
|
||||||
CONFIG.activeSensors = data.getUint16(4, true);
|
CONFIG.activeSensors = data.getUint16(4, true);
|
||||||
|
|
||||||
/* For 1.7.4+ MSP_ACTIVEBOXES should be used to determine active modes */
|
|
||||||
if (semver.lt(CONFIG.flightControllerVersion, "1.7.4")) {
|
|
||||||
CONFIG.mode = data.getUint32(6, true);
|
|
||||||
}
|
|
||||||
|
|
||||||
CONFIG.profile = data.getUint8(10);
|
CONFIG.profile = data.getUint8(10);
|
||||||
CONFIG.cpuload = data.getUint16(11, true);
|
CONFIG.cpuload = data.getUint16(11, true);
|
||||||
CONFIG.armingFlags = data.getUint16(13, true);
|
CONFIG.armingFlags = data.getUint16(13, true);
|
||||||
|
@ -867,12 +861,10 @@ var mspHelper = (function (gui) {
|
||||||
RX_CONFIG.spirx_channel_count = data.getUint8(offset);
|
RX_CONFIG.spirx_channel_count = data.getUint8(offset);
|
||||||
offset += 1;
|
offset += 1;
|
||||||
}
|
}
|
||||||
if (semver.gt(CONFIG.flightControllerVersion, "1.7.3")) {
|
|
||||||
// unused byte for fpvCamAngleDegrees, for compatiblity with betaflight
|
// unused byte for fpvCamAngleDegrees, for compatiblity with betaflight
|
||||||
offset += 1;
|
offset += 1;
|
||||||
RX_CONFIG.receiver_type = data.getUint8(offset);
|
RX_CONFIG.receiver_type = data.getUint8(offset);
|
||||||
offset += 1;
|
offset += 1;
|
||||||
}
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSPCodes.MSP_FAILSAFE_CONFIG:
|
case MSPCodes.MSP_FAILSAFE_CONFIG:
|
||||||
|
@ -888,7 +880,6 @@ var mspHelper = (function (gui) {
|
||||||
offset += 2;
|
offset += 2;
|
||||||
FAILSAFE_CONFIG.failsafe_procedure = data.getUint8(offset);
|
FAILSAFE_CONFIG.failsafe_procedure = data.getUint8(offset);
|
||||||
offset++;
|
offset++;
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.7.3")) {
|
|
||||||
FAILSAFE_CONFIG.failsafe_recovery_delay = data.getUint8(offset);
|
FAILSAFE_CONFIG.failsafe_recovery_delay = data.getUint8(offset);
|
||||||
offset++;
|
offset++;
|
||||||
FAILSAFE_CONFIG.failsafe_fw_roll_angle = data.getUint16(offset, true);
|
FAILSAFE_CONFIG.failsafe_fw_roll_angle = data.getUint16(offset, true);
|
||||||
|
@ -899,13 +890,10 @@ var mspHelper = (function (gui) {
|
||||||
offset += 2;
|
offset += 2;
|
||||||
FAILSAFE_CONFIG.failsafe_stick_motion_threshold = data.getUint16(offset, true);
|
FAILSAFE_CONFIG.failsafe_stick_motion_threshold = data.getUint16(offset, true);
|
||||||
offset += 2;
|
offset += 2;
|
||||||
}
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.7.4")) {
|
|
||||||
FAILSAFE_CONFIG.failsafe_min_distance = data.getUint16(offset, true);
|
FAILSAFE_CONFIG.failsafe_min_distance = data.getUint16(offset, true);
|
||||||
offset += 2;
|
offset += 2;
|
||||||
FAILSAFE_CONFIG.failsafe_min_distance_procedure = data.getUint8(offset);
|
FAILSAFE_CONFIG.failsafe_min_distance_procedure = data.getUint8(offset);
|
||||||
offset++;
|
offset++;
|
||||||
}
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSPCodes.MSP_RXFAIL_CONFIG:
|
case MSPCodes.MSP_RXFAIL_CONFIG:
|
||||||
|
@ -1702,12 +1690,10 @@ var mspHelper = (function (gui) {
|
||||||
buffer.push32(RX_CONFIG.spirx_id);
|
buffer.push32(RX_CONFIG.spirx_id);
|
||||||
buffer.push(RX_CONFIG.spirx_channel_count);
|
buffer.push(RX_CONFIG.spirx_channel_count);
|
||||||
}
|
}
|
||||||
if (semver.gt(CONFIG.flightControllerVersion, "1.7.3")) {
|
|
||||||
// unused byte for fpvCamAngleDegrees, for compatiblity with betaflight
|
// unused byte for fpvCamAngleDegrees, for compatiblity with betaflight
|
||||||
buffer.push(0);
|
buffer.push(0);
|
||||||
// receiver type in RX_CONFIG rather than in BF_CONFIG.features
|
// receiver type in RX_CONFIG rather than in BF_CONFIG.features
|
||||||
buffer.push(RX_CONFIG.receiver_type);
|
buffer.push(RX_CONFIG.receiver_type);
|
||||||
}
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSPCodes.MSP_SET_FAILSAFE_CONFIG:
|
case MSPCodes.MSP_SET_FAILSAFE_CONFIG:
|
||||||
|
@ -1719,7 +1705,6 @@ var mspHelper = (function (gui) {
|
||||||
buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_throttle_low_delay));
|
buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_throttle_low_delay));
|
||||||
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_throttle_low_delay));
|
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_throttle_low_delay));
|
||||||
buffer.push(FAILSAFE_CONFIG.failsafe_procedure);
|
buffer.push(FAILSAFE_CONFIG.failsafe_procedure);
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.7.3")) {
|
|
||||||
buffer.push(FAILSAFE_CONFIG.failsafe_recovery_delay);
|
buffer.push(FAILSAFE_CONFIG.failsafe_recovery_delay);
|
||||||
buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_fw_roll_angle));
|
buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_fw_roll_angle));
|
||||||
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_fw_roll_angle));
|
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_fw_roll_angle));
|
||||||
|
@ -1729,12 +1714,9 @@ var mspHelper = (function (gui) {
|
||||||
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_fw_yaw_rate));
|
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_fw_yaw_rate));
|
||||||
buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_stick_motion_threshold));
|
buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_stick_motion_threshold));
|
||||||
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_stick_motion_threshold));
|
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_stick_motion_threshold));
|
||||||
}
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.7.4")) {
|
|
||||||
buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_min_distance));
|
buffer.push(lowByte(FAILSAFE_CONFIG.failsafe_min_distance));
|
||||||
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_min_distance));
|
buffer.push(highByte(FAILSAFE_CONFIG.failsafe_min_distance));
|
||||||
buffer.push(FAILSAFE_CONFIG.failsafe_min_distance_procedure);
|
buffer.push(FAILSAFE_CONFIG.failsafe_min_distance_procedure);
|
||||||
}
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSPCodes.MSP_SET_TRANSPONDER_CONFIG:
|
case MSPCodes.MSP_SET_TRANSPONDER_CONFIG:
|
||||||
|
@ -2897,35 +2879,19 @@ var mspHelper = (function (gui) {
|
||||||
};
|
};
|
||||||
|
|
||||||
self.loadRthAndLandConfig = function (callback) {
|
self.loadRthAndLandConfig = function (callback) {
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.7.1")) {
|
|
||||||
MSP.send_message(MSPCodes.MSP_RTH_AND_LAND_CONFIG, false, false, callback);
|
MSP.send_message(MSPCodes.MSP_RTH_AND_LAND_CONFIG, false, false, callback);
|
||||||
} else {
|
|
||||||
callback();
|
|
||||||
}
|
|
||||||
};
|
};
|
||||||
|
|
||||||
self.saveRthAndLandConfig = function (callback) {
|
self.saveRthAndLandConfig = function (callback) {
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.7.1")) {
|
|
||||||
MSP.send_message(MSPCodes.MSP_SET_RTH_AND_LAND_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_RTH_AND_LAND_CONFIG), false, callback);
|
MSP.send_message(MSPCodes.MSP_SET_RTH_AND_LAND_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_RTH_AND_LAND_CONFIG), false, callback);
|
||||||
} else {
|
|
||||||
callback();
|
|
||||||
}
|
|
||||||
};
|
};
|
||||||
|
|
||||||
self.loadFwConfig = function (callback) {
|
self.loadFwConfig = function (callback) {
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.7.1")) {
|
|
||||||
MSP.send_message(MSPCodes.MSP_FW_CONFIG, false, false, callback);
|
MSP.send_message(MSPCodes.MSP_FW_CONFIG, false, false, callback);
|
||||||
} else {
|
|
||||||
callback();
|
|
||||||
}
|
|
||||||
};
|
};
|
||||||
|
|
||||||
self.saveFwConfig = function (callback) {
|
self.saveFwConfig = function (callback) {
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.7.1")) {
|
|
||||||
MSP.send_message(MSPCodes.MSP_SET_FW_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FW_CONFIG), false, callback);
|
MSP.send_message(MSPCodes.MSP_SET_FW_CONFIG, mspHelper.crunch(MSPCodes.MSP_SET_FW_CONFIG), false, callback);
|
||||||
} else {
|
|
||||||
callback();
|
|
||||||
}
|
|
||||||
};
|
};
|
||||||
|
|
||||||
self.getMissionInfo = function (callback) {
|
self.getMissionInfo = function (callback) {
|
||||||
|
@ -3117,7 +3083,6 @@ var mspHelper = (function (gui) {
|
||||||
};
|
};
|
||||||
|
|
||||||
self.getRTC = function (callback) {
|
self.getRTC = function (callback) {
|
||||||
if (semver.gt(CONFIG.flightControllerVersion, "1.7.3")) {
|
|
||||||
MSP.send_message(MSPCodes.MSP_RTC, false, false, function (resp) {
|
MSP.send_message(MSPCodes.MSP_RTC, false, false, function (resp) {
|
||||||
var seconds = resp.data.read32();
|
var seconds = resp.data.read32();
|
||||||
var millis = resp.data.readU16();
|
var millis = resp.data.readU16();
|
||||||
|
@ -3125,13 +3090,9 @@ var mspHelper = (function (gui) {
|
||||||
callback(seconds, millis);
|
callback(seconds, millis);
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
} else if (callback) {
|
|
||||||
callback(0, 0);
|
|
||||||
}
|
|
||||||
};
|
};
|
||||||
|
|
||||||
self.setRTC = function (callback) {
|
self.setRTC = function (callback) {
|
||||||
if (semver.gt(CONFIG.flightControllerVersion, "1.7.3")) {
|
|
||||||
var now = Date.now();
|
var now = Date.now();
|
||||||
var secs = now / 1000;
|
var secs = now / 1000;
|
||||||
var millis = now % 1000;
|
var millis = now % 1000;
|
||||||
|
@ -3139,9 +3100,6 @@ var mspHelper = (function (gui) {
|
||||||
data.push32(secs);
|
data.push32(secs);
|
||||||
data.push16(millis);
|
data.push16(millis);
|
||||||
MSP.send_message(MSPCodes.MSP_SET_RTC, data, false, callback);
|
MSP.send_message(MSPCodes.MSP_SET_RTC, data, false, callback);
|
||||||
} else if (callback) {
|
|
||||||
callback();
|
|
||||||
}
|
|
||||||
};
|
};
|
||||||
|
|
||||||
self.loadServoConfiguration = function (callback) {
|
self.loadServoConfiguration = function (callback) {
|
||||||
|
|
|
@ -58,7 +58,7 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="config-section gui_box grey requires-v1_7_1">
|
<div class="config-section gui_box grey">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title" data-i18n="rthConfiguration"></div>
|
<div class="spacer_box_title" data-i18n="rthConfiguration"></div>
|
||||||
</div>
|
</div>
|
||||||
|
@ -214,7 +214,7 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="config-section gui_box grey requires-v1_7_1">
|
<div class="config-section gui_box grey">
|
||||||
<div class="gui_box_titlebar">
|
<div class="gui_box_titlebar">
|
||||||
<div class="spacer_box_title" data-i18n="fixedWingNavigationConfiguration"></div>
|
<div class="spacer_box_title" data-i18n="fixedWingNavigationConfiguration"></div>
|
||||||
</div>
|
</div>
|
||||||
|
|
|
@ -68,8 +68,6 @@ TABS.advanced_tuning.initialize = function (callback) {
|
||||||
$('.requires-v2_1').hide();
|
$('.requires-v2_1').hide();
|
||||||
}
|
}
|
||||||
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.7.1")) {
|
|
||||||
|
|
||||||
$rthClimbFirst.prop("checked", RTH_AND_LAND_CONFIG.rthClimbFirst);
|
$rthClimbFirst.prop("checked", RTH_AND_LAND_CONFIG.rthClimbFirst);
|
||||||
$rthClimbFirst.change(function () {
|
$rthClimbFirst.change(function () {
|
||||||
if ($(this).is(":checked")) {
|
if ($(this).is(":checked")) {
|
||||||
|
@ -111,11 +109,6 @@ TABS.advanced_tuning.initialize = function (callback) {
|
||||||
RTH_AND_LAND_CONFIG.rthAllowLanding = $rthAllowLanding.val();
|
RTH_AND_LAND_CONFIG.rthAllowLanding = $rthAllowLanding.val();
|
||||||
});
|
});
|
||||||
|
|
||||||
$('.requires-v1_7_1').show();
|
|
||||||
} else {
|
|
||||||
$('.requires-v1_7_1').hide();
|
|
||||||
}
|
|
||||||
|
|
||||||
GUI.fillSelect($userControlMode, FC.getUserControlMode(), NAV_POSHOLD.userControlMode);
|
GUI.fillSelect($userControlMode, FC.getUserControlMode(), NAV_POSHOLD.userControlMode);
|
||||||
$userControlMode.val(NAV_POSHOLD.userControlMode);
|
$userControlMode.val(NAV_POSHOLD.userControlMode);
|
||||||
$userControlMode.change(function () {
|
$userControlMode.change(function () {
|
||||||
|
|
|
@ -51,7 +51,7 @@
|
||||||
<label for="sensor-pitot"> <span data-i18n="sensorPitot"></span></label>
|
<label for="sensor-pitot"> <span data-i18n="sensorPitot"></span></label>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="select requires-v1_7">
|
<div class="select">
|
||||||
<select id="sensor-rangefinder"></select>
|
<select id="sensor-rangefinder"></select>
|
||||||
<label for="sensor-rangefinder"> <span data-i18n="sensorRangefinder"></span></label>
|
<label for="sensor-rangefinder"> <span data-i18n="sensorRangefinder"></span></label>
|
||||||
</div>
|
</div>
|
||||||
|
|
|
@ -736,12 +736,6 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
|
||||||
SENSOR_CONFIG.opflow = $sensorOpflow.val();
|
SENSOR_CONFIG.opflow = $sensorOpflow.val();
|
||||||
});
|
});
|
||||||
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.7.0")) {
|
|
||||||
$(".requires-v1_7").show();
|
|
||||||
} else {
|
|
||||||
$(".requires-v1_7").hide();
|
|
||||||
}
|
|
||||||
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.8.1")) {
|
if (semver.gte(CONFIG.flightControllerVersion, "1.8.1")) {
|
||||||
$(".requires-v1_8_1").show();
|
$(".requires-v1_8_1").show();
|
||||||
} else {
|
} else {
|
||||||
|
|
|
@ -80,7 +80,6 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
<!-- Minimum Failsafe Distance controls -->
|
<!-- Minimum Failsafe Distance controls -->
|
||||||
<div class="requires-v1_7_4">
|
|
||||||
<div class="checkbox stage2">
|
<div class="checkbox stage2">
|
||||||
<div class="numberspacer" >
|
<div class="numberspacer" >
|
||||||
<input type="checkbox" name="failsafe_use_minimum_distance" class="toggle" id="failsafe_use_minimum_distance" />
|
<input type="checkbox" name="failsafe_use_minimum_distance" class="toggle" id="failsafe_use_minimum_distance" />
|
||||||
|
@ -106,7 +105,6 @@
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
|
||||||
<div class="content_toolbar">
|
<div class="content_toolbar">
|
||||||
<div class="btn save_btn">
|
<div class="btn save_btn">
|
||||||
<a class="save" href="#" data-i18n="configurationButtonSave"></a>
|
<a class="save" href="#" data-i18n="configurationButtonSave"></a>
|
||||||
|
|
|
@ -196,9 +196,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
||||||
$('input[name="failsafe_off_delay"]').val(FAILSAFE_CONFIG.failsafe_off_delay);
|
$('input[name="failsafe_off_delay"]').val(FAILSAFE_CONFIG.failsafe_off_delay);
|
||||||
$('input[name="failsafe_throttle_low_delay"]').val(FAILSAFE_CONFIG.failsafe_throttle_low_delay);
|
$('input[name="failsafe_throttle_low_delay"]').val(FAILSAFE_CONFIG.failsafe_throttle_low_delay);
|
||||||
$('input[name="failsafe_delay"]').val(FAILSAFE_CONFIG.failsafe_delay);
|
$('input[name="failsafe_delay"]').val(FAILSAFE_CONFIG.failsafe_delay);
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.7.4")) {
|
|
||||||
$('input[name="failsafe_min_distance"]').val(FAILSAFE_CONFIG.failsafe_min_distance);
|
$('input[name="failsafe_min_distance"]').val(FAILSAFE_CONFIG.failsafe_min_distance);
|
||||||
}
|
|
||||||
|
|
||||||
// set stage 2 failsafe procedure
|
// set stage 2 failsafe procedure
|
||||||
$('input[type="radio"].procedure').change(function () {
|
$('input[type="radio"].procedure').change(function () {
|
||||||
|
@ -249,7 +247,6 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
||||||
// set stage 2 kill switch option
|
// set stage 2 kill switch option
|
||||||
$('input[name="failsafe_kill_switch"]').prop('checked', FAILSAFE_CONFIG.failsafe_kill_switch);
|
$('input[name="failsafe_kill_switch"]').prop('checked', FAILSAFE_CONFIG.failsafe_kill_switch);
|
||||||
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.7.4")) {
|
|
||||||
// Adjust Minimum Distance values when checkbox is checked/unchecked
|
// Adjust Minimum Distance values when checkbox is checked/unchecked
|
||||||
$failsafeUseMinimumDistanceCheckbox.change(function() {
|
$failsafeUseMinimumDistanceCheckbox.change(function() {
|
||||||
if ($(this).is(':checked')) {
|
if ($(this).is(':checked')) {
|
||||||
|
@ -282,10 +279,6 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
||||||
$failsafeMinDistanceProcedure.change(function () {
|
$failsafeMinDistanceProcedure.change(function () {
|
||||||
FAILSAFE_CONFIG.failsafe_min_distance_procedure = $failsafeMinDistanceProcedure.val();
|
FAILSAFE_CONFIG.failsafe_min_distance_procedure = $failsafeMinDistanceProcedure.val();
|
||||||
});
|
});
|
||||||
$('.requires-v1_7_4').show();
|
|
||||||
} else {
|
|
||||||
$('.requires-v1_7_4').hide();
|
|
||||||
}
|
|
||||||
|
|
||||||
$('a.save').click(function () {
|
$('a.save').click(function () {
|
||||||
// gather data that doesn't have automatic change event bound
|
// gather data that doesn't have automatic change event bound
|
||||||
|
@ -296,9 +289,7 @@ TABS.failsafe.initialize = function (callback, scrollPosition) {
|
||||||
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());
|
||||||
FAILSAFE_CONFIG.failsafe_delay = parseInt($('input[name="failsafe_delay"]').val());
|
FAILSAFE_CONFIG.failsafe_delay = parseInt($('input[name="failsafe_delay"]').val());
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.7.4")) {
|
|
||||||
FAILSAFE_CONFIG.failsafe_min_distance = parseInt($('input[name="failsafe_min_distance"]').val());
|
FAILSAFE_CONFIG.failsafe_min_distance = parseInt($('input[name="failsafe_min_distance"]').val());
|
||||||
}
|
|
||||||
|
|
||||||
if ($('input[id="land"]').is(':checked')) {
|
if ($('input[id="land"]').is(':checked')) {
|
||||||
FAILSAFE_CONFIG.failsafe_procedure = 0;
|
FAILSAFE_CONFIG.failsafe_procedure = 0;
|
||||||
|
|
16
tabs/osd.js
16
tabs/osd.js
|
@ -349,11 +349,8 @@ function altitude_alarm_from_display(osd_data, value) {
|
||||||
// depending on the OSD display unit used (hence, no conversion)
|
// depending on the OSD display unit used (hence, no conversion)
|
||||||
function altitude_alarm_display_function(fn) {
|
function altitude_alarm_display_function(fn) {
|
||||||
return function(osd_data, value) {
|
return function(osd_data, value) {
|
||||||
if (semver.gt(CONFIG.flightControllerVersion, '1.7.3')) {
|
|
||||||
return fn(osd_data, value)
|
return fn(osd_data, value)
|
||||||
}
|
}
|
||||||
return value;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
function osdMainBatteryPreview() {
|
function osdMainBatteryPreview() {
|
||||||
|
@ -433,7 +430,7 @@ OSD.constants = {
|
||||||
UNIT_TYPES: [
|
UNIT_TYPES: [
|
||||||
{name: 'osdUnitImperial', value: 0},
|
{name: 'osdUnitImperial', value: 0},
|
||||||
{name: 'osdUnitMetric', value: 1},
|
{name: 'osdUnitMetric', value: 1},
|
||||||
{name: 'osdUnitUK', tip: 'osdUnitUKTip', value: 2, min_version: "1.7.3"},
|
{name: 'osdUnitUK', tip: 'osdUnitUKTip', value: 2},
|
||||||
],
|
],
|
||||||
AHISIDEBARWIDTHPOSITION: 7,
|
AHISIDEBARWIDTHPOSITION: 7,
|
||||||
AHISIDEBARHEIGHTPOSITION: 3,
|
AHISIDEBARHEIGHTPOSITION: 3,
|
||||||
|
@ -560,7 +557,6 @@ OSD.constants = {
|
||||||
{
|
{
|
||||||
name: 'MAIN_BATT_CELL_VOLTAGE',
|
name: 'MAIN_BATT_CELL_VOLTAGE',
|
||||||
id: 32,
|
id: 32,
|
||||||
min_version: '1.7.4',
|
|
||||||
preview: FONT.symbol(SYM.VOLT) + FONT.embed_dot('3.90V')
|
preview: FONT.symbol(SYM.VOLT) + FONT.embed_dot('3.90V')
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
|
@ -607,7 +603,6 @@ OSD.constants = {
|
||||||
{
|
{
|
||||||
name: 'THROTTLE_POSITION_AUTO_THR',
|
name: 'THROTTLE_POSITION_AUTO_THR',
|
||||||
id: 33,
|
id: 33,
|
||||||
min_version: '1.7.4',
|
|
||||||
preview: FONT.symbol(SYM.THR) + FONT.symbol(SYM.THR1) + ' 51'
|
preview: FONT.symbol(SYM.THR) + FONT.symbol(SYM.THR1) + ' 51'
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
|
@ -623,7 +618,6 @@ OSD.constants = {
|
||||||
{
|
{
|
||||||
name: 'MESSAGES',
|
name: 'MESSAGES',
|
||||||
id: 30,
|
id: 30,
|
||||||
min_version: '1.7.4',
|
|
||||||
preview: ' SYSTEM MESSAGE ', // 28 chars, like OSD_MESSAGE_LENGTH on osd.c
|
preview: ' SYSTEM MESSAGE ', // 28 chars, like OSD_MESSAGE_LENGTH on osd.c
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
|
@ -634,7 +628,6 @@ OSD.constants = {
|
||||||
{
|
{
|
||||||
name: 'HEADING_GRAPH',
|
name: 'HEADING_GRAPH',
|
||||||
id: 34,
|
id: 34,
|
||||||
min_version: '1.7.4',
|
|
||||||
preview: FONT.symbol(SYM.HEADING_W) +
|
preview: FONT.symbol(SYM.HEADING_W) +
|
||||||
FONT.symbol(SYM.HEADING_LINE) +
|
FONT.symbol(SYM.HEADING_LINE) +
|
||||||
FONT.symbol(SYM.HEADING_DIVIDED_LINE) +
|
FONT.symbol(SYM.HEADING_DIVIDED_LINE) +
|
||||||
|
@ -648,7 +641,6 @@ OSD.constants = {
|
||||||
{
|
{
|
||||||
name: 'AIR_SPEED',
|
name: 'AIR_SPEED',
|
||||||
id: 27,
|
id: 27,
|
||||||
min_version: '1.7.3',
|
|
||||||
enabled: function() {
|
enabled: function() {
|
||||||
return SENSOR_CONFIG.pitot != 0;
|
return SENSOR_CONFIG.pitot != 0;
|
||||||
},
|
},
|
||||||
|
@ -666,7 +658,6 @@ OSD.constants = {
|
||||||
{
|
{
|
||||||
name: 'RTC_TIME',
|
name: 'RTC_TIME',
|
||||||
id: 29,
|
id: 29,
|
||||||
min_version: '1.7.4',
|
|
||||||
preview: FONT.symbol(SYM.CLOCK) + '13:37'
|
preview: FONT.symbol(SYM.CLOCK) + '13:37'
|
||||||
},
|
},
|
||||||
]
|
]
|
||||||
|
@ -852,7 +843,6 @@ OSD.constants = {
|
||||||
{
|
{
|
||||||
name: 'ONTIME_FLYTIME',
|
name: 'ONTIME_FLYTIME',
|
||||||
id: 28,
|
id: 28,
|
||||||
min_version: '1.7.4',
|
|
||||||
preview: FONT.symbol(SYM.FLY_M) + '04:11'
|
preview: FONT.symbol(SYM.FLY_M) + '04:11'
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
|
@ -939,7 +929,6 @@ OSD.constants = {
|
||||||
{
|
{
|
||||||
name: 'EFFICIENCY_MAH',
|
name: 'EFFICIENCY_MAH',
|
||||||
id: 35,
|
id: 35,
|
||||||
min_version: '1.7.4',
|
|
||||||
preview: "123" + FONT.symbol(SYM.MAH_KM_0) + FONT.symbol(SYM.MAH_KM_1)
|
preview: "123" + FONT.symbol(SYM.MAH_KM_0) + FONT.symbol(SYM.MAH_KM_1)
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
|
@ -1054,7 +1043,6 @@ OSD.constants = {
|
||||||
{
|
{
|
||||||
name: 'GPS_HDOP',
|
name: 'GPS_HDOP',
|
||||||
id: 31,
|
id: 31,
|
||||||
min_version: '1.7.4',
|
|
||||||
preview: FONT.symbol(SYM.GPS_HDP1) + FONT.symbol(SYM.GPS_HDP2) + FONT.embed_dot('1.8')
|
preview: FONT.symbol(SYM.GPS_HDP1) + FONT.symbol(SYM.GPS_HDP2) + FONT.embed_dot('1.8')
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
|
@ -1631,10 +1619,8 @@ OSD.msp = {
|
||||||
d.alarms.fly_minutes = view.readU16();
|
d.alarms.fly_minutes = view.readU16();
|
||||||
d.alarms.max_altitude = view.readU16();
|
d.alarms.max_altitude = view.readU16();
|
||||||
|
|
||||||
if (semver.gt(CONFIG.flightControllerVersion, '1.7.3')) {
|
|
||||||
d.alarms.dist = view.readU16();
|
d.alarms.dist = view.readU16();
|
||||||
d.alarms.max_neg_altitude = view.readU16();
|
d.alarms.max_neg_altitude = view.readU16();
|
||||||
}
|
|
||||||
|
|
||||||
d.items = [];
|
d.items = [];
|
||||||
// start at the offset from the other fields
|
// start at the offset from the other fields
|
||||||
|
|
|
@ -43,15 +43,12 @@ TABS.ports.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// support configure RunCam Device
|
// support configure RunCam Device
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.7.3")) {
|
|
||||||
functionRules.push({
|
functionRules.push({
|
||||||
name: 'RUNCAM_DEVICE_CONTROL',
|
name: 'RUNCAM_DEVICE_CONTROL',
|
||||||
groups: ['peripherals'],
|
groups: ['peripherals'],
|
||||||
maxPorts: 1 }
|
maxPorts: 1 }
|
||||||
);
|
);
|
||||||
}
|
|
||||||
|
|
||||||
if (semver.gte(CONFIG.flightControllerVersion, "1.7.4")) {
|
|
||||||
functionRules.push({
|
functionRules.push({
|
||||||
name: 'TBS_SMARTAUDIO',
|
name: 'TBS_SMARTAUDIO',
|
||||||
groups: ['peripherals'],
|
groups: ['peripherals'],
|
||||||
|
@ -62,7 +59,6 @@ TABS.ports.initialize = function (callback) {
|
||||||
groups: ['peripherals'],
|
groups: ['peripherals'],
|
||||||
maxPorts: 1 }
|
maxPorts: 1 }
|
||||||
);
|
);
|
||||||
}
|
|
||||||
|
|
||||||
for (var i = 0; i < functionRules.length; i++) {
|
for (var i = 0; i < functionRules.length; i++) {
|
||||||
functionRules[i].displayName = chrome.i18n.getMessage('portsFunction_' + functionRules[i].name);
|
functionRules[i].displayName = chrome.i18n.getMessage('portsFunction_' + functionRules[i].name);
|
||||||
|
|
|
@ -546,12 +546,8 @@ presets.model = (function () {
|
||||||
if (mixerType == 'airplane' || mixerType == 'flyingwing') {
|
if (mixerType == 'airplane' || mixerType == 'flyingwing') {
|
||||||
// Always set MOTOR_STOP and feature AIRMODE for fixed wing
|
// Always set MOTOR_STOP and feature AIRMODE for fixed wing
|
||||||
window.BF_CONFIG.features |= 1 << 4; // MOTOR_STOP
|
window.BF_CONFIG.features |= 1 << 4; // MOTOR_STOP
|
||||||
if (semver.gt(CONFIG.flightControllerVersion, '1.7.2')) {
|
|
||||||
// Note that feature_AIRMODE is only supported on
|
|
||||||
// INAV > 1.7.2.
|
|
||||||
window.BF_CONFIG.features |= 1 << 22; // AIRMODE
|
window.BF_CONFIG.features |= 1 << 22; // AIRMODE
|
||||||
}
|
}
|
||||||
}
|
|
||||||
};
|
};
|
||||||
|
|
||||||
self.extractPresetNames = function (presets) {
|
self.extractPresetNames = function (presets) {
|
||||||
|
@ -643,13 +639,11 @@ TABS.profiles.initialize = function (callback, scrollPosition) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
var promises = {};
|
var promises = {};
|
||||||
if (semver.gt(CONFIG.flightControllerVersion, '1.7.3')) {
|
|
||||||
var settings = presets.settings.get(currentPreset.type);
|
var settings = presets.settings.get(currentPreset.type);
|
||||||
Object.keys(settings).forEach(function(key, ii) {
|
Object.keys(settings).forEach(function(key, ii) {
|
||||||
var value = settings[key];
|
var value = settings[key];
|
||||||
promises[key] = mspHelper.setSetting(name, value);
|
promises[key] = mspHelper.setSetting(name, value);
|
||||||
});
|
});
|
||||||
}
|
|
||||||
Promise.props(promises).then(function () {
|
Promise.props(promises).then(function () {
|
||||||
saveChainer.execute();
|
saveChainer.execute();
|
||||||
});
|
});
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue