Skip to content

Commit

Permalink
Add gyro and magnetic custom alignment MSP (#4294)
Browse files Browse the repository at this point in the history
* Custom alignment

* Move declination to configuration

* Cleanup unused message

* Remove unused legacy_gyro_alignment

* Remove unused legacy_accel_alignment

* Cleanup gyro_align_content

* Cleanup unused acc code

* Disable custom fields when preset is used

* Remove more 0xDEADC0DE
  • Loading branch information
haslinghuis authored Jan 10, 2025
1 parent f109371 commit e5d9cfb
Show file tree
Hide file tree
Showing 8 changed files with 295 additions and 155 deletions.
53 changes: 43 additions & 10 deletions locales/en/messages.json
Original file line number Diff line number Diff line change
Expand Up @@ -1393,8 +1393,20 @@
"configurationOtherFeaturesHelp": {
"message": "<strong>Note:</strong> Not all features are supported by all flight controllers. If you enable a specific feature, and it is disabled after you hit 'Save and Reboot', it means that this feature is not supported on your board."
},
"configurationMagAlignmentHelp": {
"message": "The magnetometer alignment is the orientation of the magnetometer sensor on the flight controller board. The default is usually correct, but if you have a custom build or a flight controller with a different magnetometer orientation, you may need to adjust this setting."
},
"configurationMagDeclination": {
"message": "Magnetometer Declination"
},
"configurationMagDeclinationInput": {
"message": "Declination Degrees"
},
"configurationMagDeclinationHelp": {
"message": "The magnetic declination is the angle between magnetic north and true north. It is different for every location on earth. You can find the declination for your location on the internet"
},
"configurationBoardAlignment": {
"message": "Board and Sensor Alignment"
"message": "Board Alignment"
},
"configurationBoardAlignmentRoll": {
"message": "Roll Degrees"
Expand All @@ -1405,6 +1417,36 @@
"configurationBoardAlignmentYaw": {
"message": "Yaw Degrees"
},
"configurationGyroAlignment": {
"message": "Gyro Alignment"
},
"configurationGyroAlignmentHelp": {
"message": "The gyro alignment is the orientation of the gyro sensor on the flight controller board. The default is usually correct, but if you have a custom build or a flight controller with a different gyro orientation, you may need to adjust this setting."
},
"configurationGyroAlignmentRoll": {
"message": "$t(configurationBoardAlignmentRoll.message)"
},
"configurationGyroAlignmentPitch": {
"message": "$t(configurationBoardAlignmentPitch.message)"
},
"configurationGyroAlignmentYaw": {
"message": "$t(configurationBoardAlignmentYaw.message)"
},
"configurationMagAlignment": {
"message": "Magnetometer Alignment"
},
"configurationBoardAlignmentHelp": {
"message": "Arbitrary board rotation in degrees, to allow mounting it sideways / upside down / rotated etc. When running external sensors, use the sensor alignments (Gyro, Acc, Mag) to define sensor position independent from board orientation. "
},
"configurationMagAlignmentRoll": {
"message": "$t(configurationBoardAlignmentRoll.message)"
},
"configurationMagAlignmentPitch": {
"message": "$t(configurationBoardAlignmentPitch.message)"
},
"configurationMagAlignmentYaw": {
"message": "$t(configurationBoardAlignmentYaw.message)"
},
"configurationSensorAlignmentGyro": {
"message": "GYRO Alignment"
},
Expand Down Expand Up @@ -1432,9 +1474,6 @@
"configurationSensorAlignmentAcc": {
"message": "ACCEL Alignment"
},
"configurationSensorAlignmentMag": {
"message": "MAG Alignment"
},
"configurationSensorAlignmentDefaultOption": {
"message": "Default"
},
Expand All @@ -1453,9 +1492,6 @@
"configurationArmingHelp": {
"message": "Some Arming options may require accelerometer be enabled"
},
"configurationMagDeclination": {
"message": "Magnetometer Declination [deg]"
},
"configurationReverseMotorSwitch": {
"message": "Motor direction is reversed"
},
Expand Down Expand Up @@ -4655,9 +4691,6 @@
"pidTuningIntegratedYawHelp": {
"message": "Integrated Yaw integrates yaw P, I and D values, allowing yaw P, I and D to be tuned a bit like you'd tune pitch and roll.<br><br>Very little I is required, because the integrated P acts like I, and integrated D acts like P.<br><br>NOTE: Integrated Yaw requires use of Absolute Control, since no I is needed with Integrated Yaw."
},
"configHelp2": {
"message": "Arbitrary board rotation in degrees, to allow mounting it sideways / upside down / rotated etc. When running external sensors, use the sensor alignments (Gyro, Acc, Mag) to define sensor position independent from board orientation. "
},
"failsafeFeaturesHelpOld": {
"message": "Failsafe configuration has changed considerably. Use Betaflight <strong>v1.12.0+</strong> to enable the improved configuration panel."
},
Expand Down
9 changes: 2 additions & 7 deletions src/css/tabs/configuration.less
Original file line number Diff line number Diff line change
Expand Up @@ -19,24 +19,19 @@
background-repeat: no-repeat;
background-position: center;
}
.board_align_content {
.sensor_align_content {
display: flex;
justify-content: space-between;
width: 100%;
flex-wrap: wrap;
gap: 0.5rem;
.board_align_inputs {
.sensor_align_inputs {
display: flex;
label {
white-space: nowrap;
}
}
}
.gyro_align_content {
display: flex;
flex-direction: column;
gap: 1rem;
}
table {
td {
height: 1.75rem;
Expand Down
6 changes: 6 additions & 0 deletions src/js/fc.js
Original file line number Diff line number Diff line change
Expand Up @@ -474,6 +474,12 @@ const FC = {
gyro_to_use: 0,
gyro_1_align: 0,
gyro_2_align: 0,
gyro_align_roll: 0,
gyro_align_pitch: 0,
gyro_align_yaw: 0,
mag_align_roll: 0,
mag_align_pitch: 0,
mag_align_yaw: 0,
};

this.PID_ADVANCED_CONFIG = {
Expand Down
32 changes: 26 additions & 6 deletions src/js/msp/MSPHelper.js
Original file line number Diff line number Diff line change
Expand Up @@ -514,7 +514,9 @@ MspHelper.prototype.process_data = function (dataHandler) {
FC.MOTOR_CONFIG.use_esc_sensor = data.readU8() != 0;
break;
case MSPCodes.MSP_COMPASS_CONFIG:
FC.COMPASS_CONFIG.mag_declination = data.read16() / 10;
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_46)) {
FC.COMPASS_CONFIG.mag_declination = data.read16() / 10;
}
break;
case MSPCodes.MSP_GPS_CONFIG:
FC.GPS_CONFIG.provider = data.readU8();
Expand Down Expand Up @@ -633,6 +635,15 @@ MspHelper.prototype.process_data = function (dataHandler) {
FC.SENSOR_ALIGNMENT.gyro_to_use = data.readU8();
FC.SENSOR_ALIGNMENT.gyro_1_align = data.readU8();
FC.SENSOR_ALIGNMENT.gyro_2_align = data.readU8();
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_47)) {
FC.SENSOR_ALIGNMENT.gyro_align_roll = data.read16() / 10;
FC.SENSOR_ALIGNMENT.gyro_align_pitch = data.read16() / 10;
FC.SENSOR_ALIGNMENT.gyro_align_yaw = data.read16() / 10;

FC.SENSOR_ALIGNMENT.mag_align_roll = data.read16() / 10;
FC.SENSOR_ALIGNMENT.mag_align_pitch = data.read16() / 10;
FC.SENSOR_ALIGNMENT.mag_align_yaw = data.read16() / 10;
}
break;
case MSPCodes.MSP_DISPLAYPORT:
break;
Expand Down Expand Up @@ -773,14 +784,13 @@ MspHelper.prototype.process_data = function (dataHandler) {
FC.CONFIG.apiVersion = `${data.readU8()}.${data.readU8()}.0`;
break;

case MSPCodes.MSP_FC_VARIANT: {
case MSPCodes.MSP_FC_VARIANT:
let fcVariantIdentifier = "";
for (let i = 0; i < 4; i++) {
fcVariantIdentifier += String.fromCharCode(data.readU8());
}
FC.CONFIG.flightControllerIdentifier = fcVariantIdentifier;
break;
}

case MSPCodes.MSP_FC_VERSION:
FC.CONFIG.flightControllerVersion = `${data.readU8()}.${data.readU8()}.${data.readU8()}`;
Expand Down Expand Up @@ -899,7 +909,7 @@ MspHelper.prototype.process_data = function (dataHandler) {
console.log("Channel forwarding saved");
break;

case MSPCodes.MSP_CF_SERIAL_CONFIG: {
case MSPCodes.MSP_CF_SERIAL_CONFIG:
FC.SERIAL_CONFIG.ports = [];
const bytesPerPort = 1 + 2 + 1 * 4;

Expand All @@ -917,7 +927,6 @@ MspHelper.prototype.process_data = function (dataHandler) {
FC.SERIAL_CONFIG.ports.push(serialPort);
}
break;
}

case MSPCodes.MSP2_COMMON_SERIAL_CONFIG:
FC.SERIAL_CONFIG.ports = [];
Expand Down Expand Up @@ -1897,7 +1906,9 @@ MspHelper.prototype.crunch = function (code, modifierCode = undefined) {
buffer.push16(FC.GPS_RESCUE.initialClimbM);
break;
case MSPCodes.MSP_SET_COMPASS_CONFIG:
buffer.push16(Math.round(10.0 * parseFloat(FC.COMPASS_CONFIG.mag_declination)));
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_46)) {
buffer.push16(Math.round(10.0 * parseFloat(FC.COMPASS_CONFIG.mag_declination)));
}
break;
case MSPCodes.MSP_SET_RSSI_CONFIG:
buffer.push8(FC.RSSI_CONFIG.channel);
Expand Down Expand Up @@ -2045,6 +2056,15 @@ MspHelper.prototype.crunch = function (code, modifierCode = undefined) {
.push8(FC.SENSOR_ALIGNMENT.gyro_to_use)
.push8(FC.SENSOR_ALIGNMENT.gyro_1_align)
.push8(FC.SENSOR_ALIGNMENT.gyro_2_align);
if (semver.gte(FC.CONFIG.apiVersion, API_VERSION_1_47)) {
buffer.push16(FC.SENSOR_ALIGNMENT.gyro_align_roll * 10);
buffer.push16(FC.SENSOR_ALIGNMENT.gyro_align_pitch * 10);
buffer.push16(FC.SENSOR_ALIGNMENT.gyro_align_yaw * 10);

buffer.push16(FC.SENSOR_ALIGNMENT.mag_align_roll * 10);
buffer.push16(FC.SENSOR_ALIGNMENT.mag_align_pitch * 10);
buffer.push16(FC.SENSOR_ALIGNMENT.mag_align_yaw * 10);
}
break;
case MSPCodes.MSP_SET_ADVANCED_CONFIG:
buffer
Expand Down
Loading

0 comments on commit e5d9cfb

Please sign in to comment.