mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 21:05:35 +03:00
Support changing PID controller in the GUI.
This commit is contained in:
parent
e94e24f83a
commit
35200e5a36
10 changed files with 128 additions and 14 deletions
|
@ -508,6 +508,9 @@
|
||||||
"message": "Save and Reboot"
|
"message": "Save and Reboot"
|
||||||
},
|
},
|
||||||
|
|
||||||
|
"pidTuningUpgradeFirmwareToChangePidController": {
|
||||||
|
"message": "<span style=\"color: red\">Changing PID controller disabled - you can change it via the CLI.</span> You have firmware with API version <span style=\"color: red\">$1</span>, but this functionality requires requires <span style=\"color: green\">$2</span>."
|
||||||
|
},
|
||||||
"pidTuningName": {
|
"pidTuningName": {
|
||||||
"message": "Name"
|
"message": "Name"
|
||||||
},
|
},
|
||||||
|
@ -538,6 +541,9 @@
|
||||||
"pidTuningProfileHead": {
|
"pidTuningProfileHead": {
|
||||||
"message": "Profile"
|
"message": "Profile"
|
||||||
},
|
},
|
||||||
|
"pidTuningControllerHead": {
|
||||||
|
"message": "PID Controller"
|
||||||
|
},
|
||||||
"pidTuningLoadedProfile": {
|
"pidTuningLoadedProfile": {
|
||||||
"message": "Loaded Profile: <strong>$1</strong>"
|
"message": "Loaded Profile: <strong>$1</strong>"
|
||||||
},
|
},
|
||||||
|
|
|
@ -1,12 +1,13 @@
|
||||||
<span>2015.01.19 - 0.60.1 - cleanflight</span>
|
<span>2015.01.19 - 0.61.0 - cleanflight</span>
|
||||||
<p>
|
<p>
|
||||||
- Add support for backup and restore of LED strip configuration.<br />
|
- Support changing PID controller - there new PID controllers in 1.7.0 firmware.<br />
|
||||||
- Update presentation of LEDs that have multiple functions.<br />
|
|
||||||
- Support for LED thrust ring.<br />
|
- Support for LED thrust ring.<br />
|
||||||
- Support for LED colors.<br />
|
- Support for LED colors.<br />
|
||||||
- Support for displaying sonar sensor reading on the sensors tab.<br />
|
- Support for displaying sonar sensor reading on the sensors tab.<br />
|
||||||
- UI cleanup - 'Welcome' and 'Firmware flasher' are now tabs.<br />
|
- UI cleanup - 'Welcome' and 'Firmware flasher' are now tabs.<br />
|
||||||
|
- Update presentation of LEDs that have multiple functions.<br />
|
||||||
- Added Documentation and Support panels to welcome tab.<br />
|
- Added Documentation and Support panels to welcome tab.<br />
|
||||||
|
- Add support for backup and restore of LED strip configuration.<br />
|
||||||
- Fix for disappearing tabs in chrome 41 beta.<br />
|
- Fix for disappearing tabs in chrome 41 beta.<br />
|
||||||
</p>
|
</p>
|
||||||
<span>2015.01.08 - 0.60.0 - cleanflight</span>
|
<span>2015.01.08 - 0.60.0 - cleanflight</span>
|
||||||
|
|
|
@ -25,6 +25,7 @@ function configuration_backup(callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
var profileSpecificData = [
|
var profileSpecificData = [
|
||||||
|
MSP_codes.MSP_PID_CONTROLLER,
|
||||||
MSP_codes.MSP_PID,
|
MSP_codes.MSP_PID,
|
||||||
MSP_codes.MSP_RC_TUNING,
|
MSP_codes.MSP_RC_TUNING,
|
||||||
MSP_codes.MSP_ACC_TRIM,
|
MSP_codes.MSP_ACC_TRIM,
|
||||||
|
@ -47,7 +48,8 @@ function configuration_backup(callback) {
|
||||||
fetch_specific_data_item();
|
fetch_specific_data_item();
|
||||||
} else {
|
} else {
|
||||||
configuration.profiles.push({
|
configuration.profiles.push({
|
||||||
'PID': jQuery.extend(true, [], PIDs),
|
'PID': jQuery.extend(true, [], PID),
|
||||||
|
'PIDs': jQuery.extend(true, [], PIDs),
|
||||||
'RC': jQuery.extend(true, {}, RC_tuning),
|
'RC': jQuery.extend(true, {}, RC_tuning),
|
||||||
'AccTrim': jQuery.extend(true, [], CONFIG.accelerometerTrims),
|
'AccTrim': jQuery.extend(true, [], CONFIG.accelerometerTrims),
|
||||||
'ServoConfig': jQuery.extend(true, [], SERVO_CONFIG),
|
'ServoConfig': jQuery.extend(true, [], SERVO_CONFIG),
|
||||||
|
@ -313,6 +315,21 @@ function configuration_restore(callback) {
|
||||||
appliedMigrationsCount++;
|
appliedMigrationsCount++;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (!compareVersions(migratedVersion, '0.61.0')) {
|
||||||
|
|
||||||
|
// Changing PID controller via UI was added.
|
||||||
|
if (!configuration.PIDs && configuration.PID) {
|
||||||
|
configuration.PIDs = configuration.PID;
|
||||||
|
configuration.PID = {
|
||||||
|
controller: 0 // assume pid controller 0 was used.
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
migratedVersion = '0.61.0';
|
||||||
|
GUI.log(chrome.i18n.getMessage('configMigratedTo', [migratedVersion]));
|
||||||
|
appliedMigrationsCount++;
|
||||||
|
}
|
||||||
|
|
||||||
GUI.log(chrome.i18n.getMessage('configMigrationSuccessful', [appliedMigrationsCount]));
|
GUI.log(chrome.i18n.getMessage('configMigrationSuccessful', [appliedMigrationsCount]));
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
@ -323,6 +340,7 @@ function configuration_restore(callback) {
|
||||||
profilesN = 3;
|
profilesN = 3;
|
||||||
|
|
||||||
var profileSpecificData = [
|
var profileSpecificData = [
|
||||||
|
MSP_codes.MSP_SET_PID_CONTROLLER,
|
||||||
MSP_codes.MSP_SET_PID,
|
MSP_codes.MSP_SET_PID,
|
||||||
MSP_codes.MSP_SET_RC_TUNING,
|
MSP_codes.MSP_SET_RC_TUNING,
|
||||||
MSP_codes.MSP_SET_ACC_TRIM,
|
MSP_codes.MSP_SET_ACC_TRIM,
|
||||||
|
@ -348,7 +366,8 @@ function configuration_restore(callback) {
|
||||||
codeKey = 0;
|
codeKey = 0;
|
||||||
|
|
||||||
function load_objects(profile) {
|
function load_objects(profile) {
|
||||||
PIDs = configuration.profiles[profile].PID;
|
PID = configuration.profiles[profile].PID;
|
||||||
|
PIDs = configuration.profiles[profile].PIDs;
|
||||||
RC_tuning = configuration.profiles[profile].RC;
|
RC_tuning = configuration.profiles[profile].RC;
|
||||||
CONFIG.accelerometerTrims = configuration.profiles[profile].AccTrim;
|
CONFIG.accelerometerTrims = configuration.profiles[profile].AccTrim;
|
||||||
SERVO_CONFIG = configuration.profiles[profile].ServoConfig;
|
SERVO_CONFIG = configuration.profiles[profile].ServoConfig;
|
||||||
|
|
|
@ -1,9 +1,10 @@
|
||||||
'use strict';
|
'use strict';
|
||||||
|
|
||||||
var CONFIGURATOR = {
|
var CONFIGURATOR = {
|
||||||
'releaseDate': 1421431075334, // new Date().getTime() - 2015.01.16
|
'releaseDate': 1422552160231, // new Date().getTime() - 2015.01.29
|
||||||
'apiVersionAccepted': 1.2,
|
'apiVersionAccepted': 1.2,
|
||||||
'backupRestoreMinApiVersionAccepted': 1.4,
|
'backupRestoreMinApiVersionAccepted': 1.5,
|
||||||
|
'pidControllerChangeMinApiVersion': 1.5,
|
||||||
'backupFileMinVersionAccepted': '0.55', // chrome.runtime.getManifest().version is stored as string, so does this one
|
'backupFileMinVersionAccepted': '0.55', // chrome.runtime.getManifest().version is stored as string, so does this one
|
||||||
'connectionValid': false,
|
'connectionValid': false,
|
||||||
'connectionValidCliOnly': false,
|
'connectionValidCliOnly': false,
|
||||||
|
@ -42,6 +43,9 @@ var BF_CONFIG = {
|
||||||
|
|
||||||
var LED_STRIP = [];
|
var LED_STRIP = [];
|
||||||
|
|
||||||
|
var PID = {
|
||||||
|
controller: 0
|
||||||
|
};
|
||||||
|
|
||||||
var PID_names = [];
|
var PID_names = [];
|
||||||
var PIDs = new Array(10);
|
var PIDs = new Array(10);
|
||||||
|
|
12
js/msp.js
12
js/msp.js
|
@ -20,6 +20,8 @@ var MSP_codes = {
|
||||||
MSP_CF_SERIAL_CONFIG: 54,
|
MSP_CF_SERIAL_CONFIG: 54,
|
||||||
MSP_SET_CF_SERIAL_CONFIG: 55,
|
MSP_SET_CF_SERIAL_CONFIG: 55,
|
||||||
MSP_SONAR: 58,
|
MSP_SONAR: 58,
|
||||||
|
MSP_PID_CONTROLLER: 59,
|
||||||
|
MSP_SET_PID_CONTROLLER: 60,
|
||||||
|
|
||||||
// Multiwii MSP commands
|
// Multiwii MSP commands
|
||||||
MSP_IDENT: 100,
|
MSP_IDENT: 100,
|
||||||
|
@ -673,6 +675,13 @@ var MSP = {
|
||||||
console.log('Adjustment range saved');
|
console.log('Adjustment range saved');
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MSP_codes.MSP_PID_CONTROLLER:
|
||||||
|
PID.controller = data.getUint8(0, 1);
|
||||||
|
break;
|
||||||
|
case MSP_codes.MSP_SET_PID_CONTROLLER:
|
||||||
|
console.log('PID controller changed');
|
||||||
|
break;
|
||||||
|
|
||||||
|
|
||||||
default:
|
default:
|
||||||
console.log('Unknown code detected: ' + code);
|
console.log('Unknown code detected: ' + code);
|
||||||
|
@ -806,6 +815,9 @@ MSP.crunch = function (code) {
|
||||||
buffer.push(lowByte(BF_CONFIG.currentoffset));
|
buffer.push(lowByte(BF_CONFIG.currentoffset));
|
||||||
buffer.push(highByte(BF_CONFIG.currentoffset));
|
buffer.push(highByte(BF_CONFIG.currentoffset));
|
||||||
break;
|
break;
|
||||||
|
case MSP_codes.MSP_SET_PID_CONTROLLER:
|
||||||
|
buffer.push(PID.controller);
|
||||||
|
break;
|
||||||
case MSP_codes.MSP_SET_PID:
|
case MSP_codes.MSP_SET_PID:
|
||||||
for (var i = 0; i < PIDs.length; i++) {
|
for (var i = 0; i < PIDs.length; i++) {
|
||||||
switch (i) {
|
switch (i) {
|
||||||
|
|
|
@ -171,6 +171,8 @@ function onOpen(openInfo) {
|
||||||
GUI.allowedTabs.splice(GUI.allowedTabs.indexOf('led_strip'), 1);
|
GUI.allowedTabs.splice(GUI.allowedTabs.indexOf('led_strip'), 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
GUI.canChangePidController = CONFIG.apiVersion >= CONFIGURATOR.pidControllerChangeMinApiVersion;
|
||||||
|
|
||||||
onConnect();
|
onConnect();
|
||||||
|
|
||||||
$('#tabs ul.mode-connected .tab_setup a').click();
|
$('#tabs ul.mode-connected .tab_setup a').click();
|
||||||
|
|
|
@ -1,7 +1,7 @@
|
||||||
{
|
{
|
||||||
"manifest_version": 2,
|
"manifest_version": 2,
|
||||||
"minimum_chrome_version": "38",
|
"minimum_chrome_version": "38",
|
||||||
"version": "0.60.1",
|
"version": "0.61.0",
|
||||||
"author": "Hydra",
|
"author": "Hydra",
|
||||||
"name": "Cleanflight - Configurator",
|
"name": "Cleanflight - Configurator",
|
||||||
"short_name": "cleanflight",
|
"short_name": "cleanflight",
|
||||||
|
|
|
@ -34,6 +34,30 @@
|
||||||
|
|
||||||
text-align: right;
|
text-align: right;
|
||||||
}
|
}
|
||||||
|
.tab-pid_tuning .controller {
|
||||||
|
float: left;
|
||||||
|
|
||||||
|
width: calc(18% - 2px); /* - border*/
|
||||||
|
|
||||||
|
margin-bottom: 10px;
|
||||||
|
border: 1px solid #8b8b8b;
|
||||||
|
}
|
||||||
|
.tab-pid_tuning .controller .head {
|
||||||
|
display: block;
|
||||||
|
|
||||||
|
text-align: center;
|
||||||
|
line-height: 20px;
|
||||||
|
font-weight: bold;
|
||||||
|
|
||||||
|
border-bottom: 1px solid #8b8b8b;
|
||||||
|
background-color: #ececec;
|
||||||
|
}
|
||||||
|
.tab-pid_tuning .controller select {
|
||||||
|
width: 100%;
|
||||||
|
padding-left: calc(100% - 35px);
|
||||||
|
height: 20px;
|
||||||
|
line-height: 20px;
|
||||||
|
}
|
||||||
.tab-pid_tuning .profile {
|
.tab-pid_tuning .profile {
|
||||||
float: left;
|
float: left;
|
||||||
|
|
||||||
|
|
|
@ -1,4 +1,17 @@
|
||||||
<div class="tab-pid_tuning">
|
<div class="tab-pid_tuning">
|
||||||
|
<div class="controller">
|
||||||
|
<span class="head" i18n="pidTuningControllerHead"></span>
|
||||||
|
<select name="controller">
|
||||||
|
<option value="0">MultiWii (Old)</option>
|
||||||
|
<option value="1">MultiWii (rewrite)</option>
|
||||||
|
<option value="2">LuxFloat</option>
|
||||||
|
<option value="3">MultiWii (2.3 - latest)</option>
|
||||||
|
<option value="4">MultiWii (2.3 - hybrid)</option>
|
||||||
|
<option value="5">Harakiri</option>
|
||||||
|
</select>
|
||||||
|
</div>
|
||||||
|
<div class="clear-both"></div>
|
||||||
|
|
||||||
<table class="pid_tuning">
|
<table class="pid_tuning">
|
||||||
<tr>
|
<tr>
|
||||||
<th class="name" i18n="pidTuningName"></th>
|
<th class="name" i18n="pidTuningName"></th>
|
||||||
|
|
|
@ -9,6 +9,14 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
googleAnalytics.sendAppView('PID Tuning');
|
googleAnalytics.sendAppView('PID Tuning');
|
||||||
}
|
}
|
||||||
|
|
||||||
|
function get_pid_controller() {
|
||||||
|
if (GUI.canChangePidController) {
|
||||||
|
MSP.send_message(MSP_codes.MSP_PID_CONTROLLER, false, false, get_pid_names);
|
||||||
|
} else {
|
||||||
|
get_pid_names();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
function get_pid_names() {
|
function get_pid_names() {
|
||||||
MSP.send_message(MSP_codes.MSP_PIDNAMES, false, false, get_pid_data);
|
MSP.send_message(MSP_codes.MSP_PIDNAMES, false, false, get_pid_data);
|
||||||
}
|
}
|
||||||
|
@ -26,7 +34,7 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// requesting MSP_STATUS manually because it contains CONFIG.profile
|
// requesting MSP_STATUS manually because it contains CONFIG.profile
|
||||||
MSP.send_message(MSP_codes.MSP_STATUS, false, false, get_pid_names);
|
MSP.send_message(MSP_codes.MSP_STATUS, false, false, get_pid_controller);
|
||||||
|
|
||||||
function process_html() {
|
function process_html() {
|
||||||
// translate to user-selected language
|
// translate to user-selected language
|
||||||
|
@ -181,6 +189,20 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
$('.rate-tpa input[name="yaw"]').val(RC_tuning.yaw_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));
|
$('.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
|
// Fill in currently selected profile
|
||||||
$('select[name="profile"]').val(CONFIG.profile);
|
$('select[name="profile"]').val(CONFIG.profile);
|
||||||
|
|
||||||
|
@ -261,6 +283,12 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
RC_tuning.yaw_rate = parseFloat($('.rate-tpa input[name="yaw"]').val());
|
RC_tuning.yaw_rate = parseFloat($('.rate-tpa input[name="yaw"]').val());
|
||||||
RC_tuning.dynamic_THR_PID = parseFloat($('.rate-tpa input[name="tpa"]').val());
|
RC_tuning.dynamic_THR_PID = parseFloat($('.rate-tpa input[name="tpa"]').val());
|
||||||
|
|
||||||
|
var pidController_e = $('select[name="controller"]');
|
||||||
|
|
||||||
|
function send_pids() {
|
||||||
|
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() {
|
function send_rc_tuning_changes() {
|
||||||
MSP.send_message(MSP_codes.MSP_SET_RC_TUNING, MSP.crunch(MSP_codes.MSP_SET_RC_TUNING), false, save_to_eeprom);
|
MSP.send_message(MSP_codes.MSP_SET_RC_TUNING, MSP.crunch(MSP_codes.MSP_SET_RC_TUNING), false, save_to_eeprom);
|
||||||
}
|
}
|
||||||
|
@ -271,7 +299,12 @@ TABS.pid_tuning.initialize = function (callback) {
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
|
|
||||||
MSP.send_message(MSP_codes.MSP_SET_PID, MSP.crunch(MSP_codes.MSP_SET_PID), false, send_rc_tuning_changes);
|
if (GUI.canChangePidController) {
|
||||||
|
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);
|
||||||
|
} else {
|
||||||
|
send_pids();
|
||||||
|
}
|
||||||
});
|
});
|
||||||
|
|
||||||
// status data pulled via separate timer with static speed
|
// status data pulled via separate timer with static speed
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue