Moved profile selection into PID Tuning tab. Did some visual cleanup.
parent
d3b3dfc3c6
commit
83fea65e1c
|
@ -782,6 +782,9 @@
|
|||
"pidTuningHideUnusedPids": {
|
||||
"message": "Hide unused PIDs"
|
||||
},
|
||||
"pidTuningPidSettings": {
|
||||
"message": "PID Controller Settings"
|
||||
},
|
||||
"pidTuningProportional": {
|
||||
"message": "Proportional"
|
||||
},
|
||||
|
@ -1742,16 +1745,22 @@
|
|||
"configurationMagHardware": {
|
||||
"message": "Magnetometer (if supported)"
|
||||
},
|
||||
"PIDTip": {
|
||||
"pidTuningProfile": {
|
||||
"message": "Profile"
|
||||
},
|
||||
"pidTuningProfileTip": {
|
||||
"message": "Up to 3 (2 for some controllers) different profiles can be stored on the flight controller. The profiles include all the settings on this tab. Once in the field, simple stick commands (see online instructions) can be used to switch between the profiles."
|
||||
},
|
||||
"pidTuningPidTip": {
|
||||
"message": "<b>Derivative from Error</b> provides more direct stick response and is mostly prefered for Racing.<br><br><b>Derivative from Measurement</b> provides smoother stick response what is more usefull for freestyling"
|
||||
},
|
||||
"PIDControllerTip": {
|
||||
"pidTuningPidControllerTip": {
|
||||
"message": "<b>Legacy vs Betaflight (float):</b> PID scaling and PID logic is exactly the same. Not necessarily retune needed. Legacy is old betaflight evolved rewrite, which is basic PID controller based on integer math. Betaflight PID controller uses floating point math and has many new features specifically designed for multirotor applications <br> <b>Float vs Integer:</b> PID scaling and PID logic is exactly the same. No retune needed. F1 boards have no onboard FPU and floating point math increases CPU load and integer math will improve performance, but float math might gain slightly more precision."
|
||||
},
|
||||
"FilterTip": {
|
||||
"pidTuningFilterTip": {
|
||||
"message": "<b>Gyro Soft Filter:</b> Lowpass filter for gyro. Use lower value for more filtering.<br><b>D Term Filter:</b> Lowpass filter for Dterm. Can affect D tuning. Use lower value for more filtering. <br><b>Yaw Filter:</b> Filters yaw output. It can help on setups with noisy yaw axis."
|
||||
},
|
||||
"PIDTuningTip": {
|
||||
"pidTuningPidTuningTip": {
|
||||
"message": "<b>Proportional:</b> You will notice a very strong resistant force to any attempts to move the MultiRotor<br><b>Integral:</b> Increase the ability to hold overall initial position and reduce drift, but also increase the delay in returning to initial position.<br><b>Derivative:</b> Improves the speed at which deviations are recovered, but increases noise<br><b>Rates and Expo</b>: Determine your stick feel based on these parameters. Use the graph and live 3D model to find your favourite rate setting"
|
||||
},
|
||||
"pidTuningRatesTip": {
|
||||
|
|
|
@ -283,7 +283,7 @@ var MSP = {
|
|||
CONFIG.activeSensors = data.getUint16(4, 1);
|
||||
CONFIG.mode = data.getUint32(6, 1);
|
||||
CONFIG.profile = data.getUint8(10);
|
||||
$('select[name="profilechange"]').val(CONFIG.profile);
|
||||
$('.tab-pid_tuning select[name="profilechange"]').val(CONFIG.profile);
|
||||
|
||||
sensor_status(CONFIG.activeSensors);
|
||||
$('span.i2c-error').text(CONFIG.i2cError);
|
||||
|
@ -297,9 +297,10 @@ var MSP = {
|
|||
CONFIG.profile = data.getUint8(10);
|
||||
CONFIG.cpuload = data.getUint16(11, 1);
|
||||
CONFIG.numProfiles = data.getUint8(13);
|
||||
$('select[name="profilechange"]').val(CONFIG.profile);
|
||||
if (CONFIG.numProfiles === 2) {
|
||||
$('select[name="profilechange"] .profile3').hide();
|
||||
$('.tab-pid_tuning select[name="profilechange"]').val(CONFIG.profile);
|
||||
if (semver.gte(CONFIG.flightControllerVersion, "3.0.0")
|
||||
&& CONFIG.numProfiles === 2) {
|
||||
$('.tab-pid_tuning select[name="profilechange"] .profile3').hide();
|
||||
}
|
||||
|
||||
sensor_status(CONFIG.activeSensors);
|
||||
|
|
9
main.css
9
main.css
|
@ -1516,15 +1516,6 @@ dialog {
|
|||
|
||||
}
|
||||
|
||||
#profile_change {
|
||||
color:white;
|
||||
margin-top: 16px;
|
||||
width:125px;
|
||||
float: right;
|
||||
margin-right: 0px;
|
||||
line-height: 12px;
|
||||
}
|
||||
|
||||
.dataflash-contents_global {
|
||||
margin-top: 18px;
|
||||
border: 1px solid #4A4A4A;
|
||||
|
|
11
main.html
11
main.html
|
@ -145,17 +145,6 @@
|
|||
<div class="legend">Dataflash: free space</div>
|
||||
</li>
|
||||
</ul>
|
||||
<div id="profile_change">
|
||||
<div class="dropdown dropdown-dark">
|
||||
<form name="profile-change" id="profile-change">
|
||||
<select class="dropdown-select" name="profilechange">
|
||||
<option value="0" class="profile1">Profile 1</option>
|
||||
<option value="1" class="profile2">Profile 2</option>
|
||||
<option value="2" class="profile3">Profile 3</option>
|
||||
</select>
|
||||
</form>
|
||||
</div>
|
||||
</div>
|
||||
</div>
|
||||
<div id="sensor-status" class="sensor_state mode-connected">
|
||||
<ul>
|
||||
|
|
10
main.js
10
main.js
|
@ -329,16 +329,6 @@ $(document).ready(function () {
|
|||
$(this).data('state', state);
|
||||
|
||||
});
|
||||
|
||||
var profile_e = $('select[name="profilechange"]');
|
||||
|
||||
profile_e.change(function () {
|
||||
var profile = parseInt($(this).val());
|
||||
MSP.send_message(MSP_codes.MSP_SELECT_SETTING, [profile], false, function () {
|
||||
GUI.log(chrome.i18n.getMessage('pidTuningLoadedProfile', [profile + 1]));
|
||||
updateActivatedTab();
|
||||
});
|
||||
});
|
||||
});
|
||||
|
||||
function microtime() {
|
||||
|
|
|
@ -302,33 +302,6 @@
|
|||
border-top-right-radius: 3px;
|
||||
}
|
||||
|
||||
.tab-pid_tuning .profile {
|
||||
float: left;
|
||||
border: 1px solid #ccc;
|
||||
border-radius: 3px;
|
||||
}
|
||||
|
||||
.tab-pid_tuning .profile .head {
|
||||
display: block;
|
||||
text-align: left;
|
||||
line-height: 20px;
|
||||
border-bottom: 1px solid #ccc;
|
||||
background-color: #828885;
|
||||
color: white;
|
||||
height: 19px;
|
||||
font-weight: normal;
|
||||
padding: 2px;
|
||||
padding-bottom: 3px;
|
||||
padding-left: 6px;
|
||||
}
|
||||
|
||||
.tab-pid_tuning .profile select {
|
||||
width: 100%;
|
||||
padding-left: calc(100% - 35px);
|
||||
height: 20px;
|
||||
line-height: 20px;
|
||||
}
|
||||
|
||||
.tab-pid_tuning .name {
|
||||
width: 14%;
|
||||
}
|
||||
|
@ -554,6 +527,17 @@
|
|||
}
|
||||
|
||||
|
||||
.tab-pid_tuning .profile {
|
||||
width: 100px;
|
||||
}
|
||||
|
||||
.tab-pid_tuning .profile select {
|
||||
border: 1px solid silver;
|
||||
margin-left: 5px;
|
||||
width: calc(100% - 10px);
|
||||
}
|
||||
|
||||
|
||||
.tab-pid_tuning .controller {
|
||||
width: 100px;
|
||||
}
|
||||
|
|
|
@ -9,9 +9,20 @@
|
|||
<p i18n="tuningHelp"></p>
|
||||
</div>
|
||||
</div>
|
||||
<div class="cf_column twothird">
|
||||
<div class="cf_column">
|
||||
<div class="profile single-field">
|
||||
<div class="helpicon cf_tip" i18n_title="pidTuningProfileTip" style="margin-top: 5px;"></div>
|
||||
<div class="head" i18n="pidTuningProfile"></div>
|
||||
<div class="bottomarea">
|
||||
<select name="profilechange">
|
||||
<option value="0" class="profile1">Profile 1</option>
|
||||
<option value="1" class="profile2">Profile 2</option>
|
||||
<option value="2" class="profile3">Profile 3</option>
|
||||
</select>
|
||||
</div>
|
||||
</div>
|
||||
<div class="controller single-field">
|
||||
<div class="helpicon cf_tip" i18n_title="PIDControllerTip" style="margin-top: 5px;"></div>
|
||||
<div class="helpicon cf_tip" i18n_title="pidTuningPidControllerTip" style="margin-top: 5px;"></div>
|
||||
<div class="head" i18n="pidTuningControllerHead"></div>
|
||||
<div class="bottomarea">
|
||||
<select name="controller">
|
||||
|
@ -20,7 +31,7 @@
|
|||
</div>
|
||||
</div>
|
||||
<div class="delta single-field">
|
||||
<div class="helpicon cf_tip" i18n_title="PIDTip" style="margin-top: 5px;"></div>
|
||||
<div class="helpicon cf_tip" i18n_title="pidTuningPidTip" style="margin-top: 5px;"></div>
|
||||
<div class="head">Derivative Method</div>
|
||||
<div class="bottomarea">
|
||||
<select name="delta">
|
||||
|
@ -42,7 +53,12 @@
|
|||
<div class="clear-both"></div>
|
||||
<div class="cf_column twothird">
|
||||
<div class="gui_box grey">
|
||||
<table class="new_rates">
|
||||
<table class="pid_titlebar new_rates">
|
||||
<tr>
|
||||
<th i18n="pidTuningPidSettings"></th>
|
||||
</tr>
|
||||
</table>
|
||||
<table>
|
||||
<tbody class="features pidTuning">
|
||||
<!-- table generated here -->
|
||||
</tbody>
|
||||
|
@ -50,8 +66,7 @@
|
|||
<td>
|
||||
<input type="checkbox" name="vbatpidcompensation" class="toggle" />
|
||||
</td>
|
||||
<td></td>
|
||||
<td>
|
||||
<td colspan=2>
|
||||
<div>
|
||||
<label for="vbatpidcompensation">
|
||||
<span i18n="pidTuningVbatPidCompensation"></span>
|
||||
|
@ -62,7 +77,7 @@
|
|||
</tr>
|
||||
</table>
|
||||
</div>
|
||||
<div class="gui_box grey">
|
||||
<div class="gui_box grey topspacer">
|
||||
<table class="pid_titlebar">
|
||||
<tr>
|
||||
<th class="name" i18n="pidTuningName"></th>
|
||||
|
@ -79,7 +94,7 @@
|
|||
<th colspan="8">
|
||||
<div class="pid_mode">
|
||||
<div i18n="pidTuningBasic" style="float:left;"></div>
|
||||
<div class="helpicon cf_tip" i18n_title="PIDTuningTip"></div>
|
||||
<div class="helpicon cf_tip" i18n_title="pidTuningPidTuningTip"></div>
|
||||
</div>
|
||||
</th>
|
||||
</tr>
|
||||
|
@ -238,7 +253,7 @@
|
|||
<th colspan="3">
|
||||
<div class="pid_mode">
|
||||
<div i18n="pidTuningLfpFilters" style="float: left;"> </div>
|
||||
<div class="helpicon cf_tip" i18n_title="FilterTip"></div>
|
||||
<div class="helpicon cf_tip" i18n_title="pidTuningFilterTip"></div>
|
||||
</div>
|
||||
</th>
|
||||
</tr>
|
||||
|
|
|
@ -454,6 +454,16 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
updateActivatedTab();
|
||||
});
|
||||
|
||||
var profileElement = $('.tab-pid_tuning select[name="profilechange"]');
|
||||
|
||||
profileElement.change(function () {
|
||||
var profile = parseInt($(this).val());
|
||||
MSP.send_message(MSP_codes.MSP_SELECT_SETTING, [profile], false, function () {
|
||||
GUI.log(chrome.i18n.getMessage('pidTuningLoadedProfile', [profile + 1]));
|
||||
updateActivatedTab();
|
||||
});
|
||||
});
|
||||
|
||||
$('.pid_tuning tr').each(function(){
|
||||
for(i = 0; i < PID_names.length; i++) {
|
||||
if($(this).hasClass(PID_names[i])) {
|
||||
|
|
Loading…
Reference in New Issue