1
0
Fork 0
mirror of https://github.com/betaflight/betaflight-configurator.git synced 2025-07-25 17:25:16 +03:00

Merge pull request #1338 from fujin/improve-board-and-gyro-alignment

MSP Multiple GYRO/ACC alignment support
This commit is contained in:
Michael Keller 2019-04-07 16:39:46 +12:00 committed by GitHub
commit 06c20442cd
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
6 changed files with 157 additions and 33 deletions

View file

@ -336,6 +336,10 @@ var FC = {
align_gyro: 0,
align_acc: 0,
align_mag: 0,
use_multi_gyro: 0,
gyro_to_use: 0,
gyro_1_align: 0,
gyro_2_align: 0,
};
PID_ADVANCED_CONFIG = {

View file

@ -536,6 +536,13 @@ MspHelper.prototype.process_data = function(dataHandler) {
SENSOR_ALIGNMENT.align_gyro = data.readU8();
SENSOR_ALIGNMENT.align_acc = data.readU8();
SENSOR_ALIGNMENT.align_mag = data.readU8();
if (semver.gte(CONFIG.apiVersion, '1.41.0')) {
SENSOR_ALIGNMENT.use_multi_gyro = data.readU8();
SENSOR_ALIGNMENT.gyro_to_use = data.readU8();
SENSOR_ALIGNMENT.gyro_1_align = data.readU8();
SENSOR_ALIGNMENT.gyro_2_align = data.readU8();
}
break;
case MSPCodes.MSP_DISPLAYPORT:
break;
@ -1658,6 +1665,11 @@ MspHelper.prototype.crunch = function(code) {
buffer.push8(SENSOR_ALIGNMENT.align_gyro)
.push8(SENSOR_ALIGNMENT.align_acc)
.push8(SENSOR_ALIGNMENT.align_mag);
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
buffer.push8(SENSOR_ALIGNMENT.gyro_to_use)
.push8(SENSOR_ALIGNMENT.gyro_1_align)
.push8(SENSOR_ALIGNMENT.gyro_2_align);
}
break;
case MSPCodes.MSP_SET_ADVANCED_CONFIG:
buffer.push8(PID_ADVANCED_CONFIG.gyro_sync_denom)

View file

@ -311,6 +311,26 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
// translate to user-selected language
i18n.localizePage();
var gyro_align_content_e = $('.tab-configuration .gyro_align_content');
var legacy_gyro_alignment_e = $('.tab-configuration .legacy_gyro_alignment');
var legacy_accel_alignment_e = $('.tab-configuration .legacy_accel_alignment');
// Hide the new multi gyro element by default
gyro_align_content_e.hide();
// If we are sent USE_MULTI_GYRO flag from the target, show the new element, while hiding the old ones.
if (SENSOR_ALIGNMENT.use_multi_gyro == 1) {
gyro_align_content_e.show();
legacy_gyro_alignment_e.hide();
legacy_accel_alignment_e.hide();
}
// As the gyro_to_use does not have a 'DEFAULT' 0th element enum like alingments, the 0th element 'First' is excluded from here.
var gyros = [
i18n.getMessage('configurationSensorGyroToUseSecond'),
i18n.getMessage('configurationSensorGyroToUseBoth')
];
var alignments = [
'CW 0°',
'CW 90°',
@ -326,17 +346,32 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
var orientation_acc_e = $('select.accalign');
var orientation_mag_e = $('select.magalign');
var orientation_gyro_to_use_e = $('select.gyro_to_use');
var orientation_gyro_1_align_e = $('select.gyro_1_align');
var orientation_gyro_2_align_e = $('select.gyro_2_align');
if (semver.lt(CONFIG.apiVersion, "1.15.0")) {
$('.tab-configuration .sensoralignment').hide();
} else {
for (var i = 0; i< gyros.length; i++) {
orientation_gyro_to_use_e.append('<option value="' + (i+1) + '">'+ gyros[i] + '</option>');
}
for (var i = 0; i < alignments.length; i++) {
orientation_gyro_e.append('<option value="' + (i+1) + '">'+ alignments[i] + '</option>');
orientation_acc_e.append('<option value="' + (i+1) + '">'+ alignments[i] + '</option>');
orientation_mag_e.append('<option value="' + (i+1) + '">'+ alignments[i] + '</option>');
orientation_gyro_1_align_e.append('<option value="' + (i+1) + '">'+ alignments[i] + '</option>');
orientation_gyro_2_align_e.append('<option value="' + (i+1) + '">'+ alignments[i] + '</option>');
}
orientation_gyro_e.val(SENSOR_ALIGNMENT.align_gyro);
orientation_acc_e.val(SENSOR_ALIGNMENT.align_acc);
orientation_mag_e.val(SENSOR_ALIGNMENT.align_mag);
orientation_gyro_to_use_e.val(SENSOR_ALIGNMENT.gyro_to_use);
orientation_gyro_1_align_e.val(SENSOR_ALIGNMENT.gyro_1_align);
orientation_gyro_2_align_e.val(SENSOR_ALIGNMENT.gyro_2_align);
}
// ESC protocols
@ -1023,6 +1058,11 @@ TABS.configuration.initialize = function (callback, scrollPosition) {
SENSOR_ALIGNMENT.align_gyro = parseInt(orientation_gyro_e.val());
SENSOR_ALIGNMENT.align_acc = parseInt(orientation_acc_e.val());
SENSOR_ALIGNMENT.align_mag = parseInt(orientation_mag_e.val());
if (semver.gte(CONFIG.apiVersion, "1.41.0")) {
SENSOR_ALIGNMENT.gyro_to_use = parseInt(orientation_gyro_to_use_e.val());
SENSOR_ALIGNMENT.gyro_1_align = parseInt(orientation_gyro_1_align_e.val());
SENSOR_ALIGNMENT.gyro_2_align = parseInt(orientation_gyro_2_align_e.val());
}
PID_ADVANCED_CONFIG.fast_pwm_protocol = parseInt(esc_protocol_e.val()-1);
PID_ADVANCED_CONFIG.use_unsyncedPwm = $('input[id="unsyncedPWMSwitch"]').is(':checked') ? 1 : 0;