made pid or pidController change exclusive, always refresh from FC after
save10.3.x-maintenance
parent
67c8cdcaac
commit
ca718409df
|
@ -13,6 +13,7 @@
|
|||
</div>
|
||||
<div class="clear-both"></div>
|
||||
|
||||
<form name="pid-tuning" id="pid-tuning">
|
||||
<table class="pid_tuning">
|
||||
<tr>
|
||||
<th class="name" i18n="pidTuningName"></th>
|
||||
|
@ -90,6 +91,8 @@
|
|||
<td><input type="number" name="tpa" step="0.01" min="0" max="2.55"/></td>
|
||||
</tr>
|
||||
</table>
|
||||
</form>
|
||||
|
||||
<div class="clear-both"></div>
|
||||
<div class="profile">
|
||||
<span class="head" i18n="pidTuningProfileHead"></span>
|
||||
|
|
|
@ -1,6 +1,9 @@
|
|||
'use strict';
|
||||
|
||||
TABS.pid_tuning = {};
|
||||
TABS.pid_tuning = {
|
||||
controllerChanged: true
|
||||
};
|
||||
|
||||
TABS.pid_tuning.initialize = function (callback) {
|
||||
var self = this;
|
||||
|
||||
|
@ -36,23 +39,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
// requesting MSP_STATUS manually because it contains CONFIG.profile
|
||||
MSP.send_message(MSP_codes.MSP_STATUS, false, false, get_pid_controller);
|
||||
|
||||
function process_html() {
|
||||
// translate to user-selected language
|
||||
localize();
|
||||
|
||||
// Fill in the names from PID_names array
|
||||
// this needs to be reworked, but will do for now
|
||||
$('.pid_tuning tr:eq(1) td:first').text(PID_names[0]);
|
||||
$('.pid_tuning tr:eq(2) td:first').text(PID_names[1]);
|
||||
$('.pid_tuning tr:eq(3) td:first').text(PID_names[2]);
|
||||
$('.pid_tuning tr:eq(4) td:first').text(PID_names[3]);
|
||||
$('.pid_tuning tr:eq(5) td:first').text(PID_names[9]);
|
||||
$('.pid_tuning tr:eq(6) td:first').text(PID_names[4]);
|
||||
$('.pid_tuning tr:eq(7) td:first').text(PID_names[5]);
|
||||
$('.pid_tuning tr:eq(8) td:first').text(PID_names[6]);
|
||||
$('.pid_tuning tr:eq(9) td:first').text(PID_names[7]);
|
||||
$('.pid_tuning tr:eq(10) td:first').text(PID_names[8]);
|
||||
|
||||
function data_stoarage_to_form() {
|
||||
// Fill in the data from PIDs array
|
||||
var i = 0;
|
||||
$('.pid_tuning .ROLL input').each(function () {
|
||||
|
@ -188,45 +175,9 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
$('.rate-tpa input[name="roll-pitch"]').val(RC_tuning.roll_pitch_rate.toFixed(2));
|
||||
$('.rate-tpa input[name="yaw"]').val(RC_tuning.yaw_rate.toFixed(2));
|
||||
$('.rate-tpa input[name="tpa"]').val(RC_tuning.dynamic_THR_PID.toFixed(2));
|
||||
|
||||
var pidController_e = $('select[name="controller"]');
|
||||
|
||||
if (GUI.canChangePidController) {
|
||||
pidController_e.val(PID.controller);
|
||||
} else {
|
||||
GUI.log(chrome.i18n.getMessage('pidTuningUpgradeFirmwareToChangePidController', [CONFIG.apiVersion, CONFIGURATOR.pidControllerChangeMinApiVersion]));
|
||||
|
||||
pidController_e.empty();
|
||||
pidController_e.append('<option value="">Unknown</option>');
|
||||
|
||||
pidController_e.prop('disabled', true);
|
||||
}
|
||||
|
||||
|
||||
// Fill in currently selected profile
|
||||
$('select[name="profile"]').val(CONFIG.profile);
|
||||
|
||||
// UI Hooks
|
||||
$('select[name="profile"]').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]));
|
||||
|
||||
GUI.tab_switch_cleanup(function () {
|
||||
TABS.pid_tuning.initialize();
|
||||
});
|
||||
});
|
||||
});
|
||||
|
||||
$('a.refresh').click(function () {
|
||||
GUI.tab_switch_cleanup(function () {
|
||||
GUI.log(chrome.i18n.getMessage('pidTuningDataRefreshed'));
|
||||
|
||||
TABS.pid_tuning.initialize();
|
||||
});
|
||||
});
|
||||
|
||||
$('a.update').click(function () {
|
||||
function form_to_pid_and_rc() {
|
||||
// Catch all the changes and stuff the inside PIDs array
|
||||
var i = 0;
|
||||
$('table.pid_tuning tr.ROLL input').each(function () {
|
||||
|
@ -282,11 +233,89 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
RC_tuning.roll_pitch_rate = parseFloat($('.rate-tpa input[name="roll-pitch"]').val());
|
||||
RC_tuning.yaw_rate = parseFloat($('.rate-tpa input[name="yaw"]').val());
|
||||
RC_tuning.dynamic_THR_PID = parseFloat($('.rate-tpa input[name="tpa"]').val());
|
||||
}
|
||||
|
||||
function process_html() {
|
||||
// translate to user-selected language
|
||||
localize();
|
||||
|
||||
// Fill in the names from PID_names array
|
||||
// this needs to be reworked, but will do for now
|
||||
$('.pid_tuning tr:eq(1) td:first').text(PID_names[0]);
|
||||
$('.pid_tuning tr:eq(2) td:first').text(PID_names[1]);
|
||||
$('.pid_tuning tr:eq(3) td:first').text(PID_names[2]);
|
||||
$('.pid_tuning tr:eq(4) td:first').text(PID_names[3]);
|
||||
$('.pid_tuning tr:eq(5) td:first').text(PID_names[9]);
|
||||
$('.pid_tuning tr:eq(6) td:first').text(PID_names[4]);
|
||||
$('.pid_tuning tr:eq(7) td:first').text(PID_names[5]);
|
||||
$('.pid_tuning tr:eq(8) td:first').text(PID_names[6]);
|
||||
$('.pid_tuning tr:eq(9) td:first').text(PID_names[7]);
|
||||
$('.pid_tuning tr:eq(10) td:first').text(PID_names[8]);
|
||||
|
||||
data_stoarage_to_form();
|
||||
|
||||
var pidController_e = $('select[name="controller"]');
|
||||
var profile_e = $('select[name="profile"]');
|
||||
var form_e = $('#pid-tuning');
|
||||
|
||||
if (GUI.canChangePidController) {
|
||||
pidController_e.val(PID.controller);
|
||||
} else {
|
||||
GUI.log(chrome.i18n.getMessage('pidTuningUpgradeFirmwareToChangePidController', [CONFIG.apiVersion, CONFIGURATOR.pidControllerChangeMinApiVersion]));
|
||||
|
||||
pidController_e.empty();
|
||||
pidController_e.append('<option value="">Unknown</option>');
|
||||
|
||||
pidController_e.prop('disabled', true);
|
||||
}
|
||||
|
||||
// Fill in currently selected profile
|
||||
|
||||
profile_e.val(CONFIG.profile);
|
||||
|
||||
// UI Hooks
|
||||
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]));
|
||||
|
||||
GUI.tab_switch_cleanup(function () {
|
||||
TABS.pid_tuning.initialize();
|
||||
});
|
||||
});
|
||||
});
|
||||
|
||||
$('a.refresh').click(function () {
|
||||
GUI.tab_switch_cleanup(function () {
|
||||
GUI.log(chrome.i18n.getMessage('pidTuningDataRefreshed'));
|
||||
TABS.pid_tuning.initialize();
|
||||
});
|
||||
});
|
||||
|
||||
form_e.find('input').each(function (k, item) {
|
||||
$(item).change(function () {
|
||||
pidController_e.prop("disabled", true);
|
||||
TABS.pid_tuning.controllerChanged = false;
|
||||
})
|
||||
});
|
||||
|
||||
pidController_e.change(function () {
|
||||
if (PID.controller != pidController_e.val()) {
|
||||
form_e.find('input').each(function (k, item) {
|
||||
$(item).prop('disabled', true);
|
||||
TABS.pid_tuning.controllerChanged = true;
|
||||
});
|
||||
}
|
||||
});
|
||||
|
||||
|
||||
// update == save.
|
||||
$('a.update').click(function () {
|
||||
|
||||
form_to_pid_and_rc();
|
||||
|
||||
function send_pids() {
|
||||
MSP.send_message(MSP_codes.MSP_SET_PID, MSP.crunch(MSP_codes.MSP_SET_PID), false, send_rc_tuning_changes);
|
||||
if (!TABS.pid_tuning.controllerChanged) MSP.send_message(MSP_codes.MSP_SET_PID, MSP.crunch(MSP_codes.MSP_SET_PID), false, send_rc_tuning_changes);
|
||||
}
|
||||
|
||||
function send_rc_tuning_changes() {
|
||||
|
@ -299,9 +328,14 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
});
|
||||
}
|
||||
|
||||
if (GUI.canChangePidController) {
|
||||
if (GUI.canChangePidController && TABS.pid_tuning.controllerChanged) {
|
||||
PID.controller = pidController_e.val();
|
||||
MSP.send_message(MSP_codes.MSP_SET_PID_CONTROLLER, MSP.crunch(MSP_codes.MSP_SET_PID_CONTROLLER), false, send_pids);
|
||||
MSP.send_message(MSP_codes.MSP_SET_PID_CONTROLLER, MSP.crunch(MSP_codes.MSP_SET_PID_CONTROLLER), false, function () {
|
||||
MSP.send_message(MSP_codes.MSP_EEPROM_WRITE, false, false, function () {
|
||||
GUI.log(chrome.i18n.getMessage('pidTuningEepromSaved'));
|
||||
});
|
||||
TABS.pid_tuning.initialize();
|
||||
});
|
||||
} else {
|
||||
send_pids();
|
||||
}
|
||||
|
@ -318,4 +352,4 @@ TABS.pid_tuning.initialize = function (callback) {
|
|||
|
||||
TABS.pid_tuning.cleanup = function (callback) {
|
||||
if (callback) callback();
|
||||
}
|
||||
};
|
Loading…
Reference in New Issue