1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-20 14:55:21 +03:00

Refactored arbitrary gyro and mag alignment.

The original implementation:

* removed the old 'alignment' variable
* did not require 'ALIGN_CUSTOM'
* always used rotation matrix
* had no additional per-pid-loop conditional logic.

Extract currently unused code into tests.
In preparation for either deleting or re-using in validateAndFixConfig.

Fix code style of some old boardalignment code.

De-duplicate vector rotation code.

Now that rotation code is exacted from `alignBoard` and now  doesn't use
`boardRotation` some if it was similar to the code in `rotateV` in
maths.c

Use DECIDEGREES for mag and gyro/acc custom alignments.

Use unnamed structure instead of `values`.

Redefine what 'custom' orientation means.

Move alignment test-only code into the tests.

Ensure gyro/mag custom alignment settings follow the enum variations.

This can't be applied to ALIGN_DEFAULT because, in the case of the MAG,
the default isn't actually known until the gyro is detected, see
`compassDetect`.

OMNIBUSF4/F7 - Don't use ALIGN_DEFAULT in target.h,
common_defaults_post.h does this now.

Comment cleanup.

Delete unused alignment code left from various tests/refactoring
efforts.

* Please do not squash this commit.

Fix SITL build by avoiding structure assignment with anonymous inner
struct.

The error from the build server was as follows:

```./src/main/common/sensor_alignment.c:49:5: error: missing initializer
for field ‘yaw’ of ‘struct <anonymous>’
[-Werror=missing-field-initializers]
     *sensorAlignment = CUSTOM_ALIGN_CW0_DEG;
     ^
In file included from ./src/main/common/sensor_alignment.c:27:0:
./src/main/common/sensor_alignment.h:80:17: note: ‘yaw’ declared here
         int16_t yaw;
                 ^
```

Cleanup sensor_alignment API.
This commit is contained in:
Dominic Clifton 2019-06-26 00:12:51 +02:00 committed by mikeller
parent 494b559277
commit 980df1536f
27 changed files with 558 additions and 139 deletions

View file

@ -320,12 +320,18 @@ bool accInit(uint32_t gyroSamplingInverval)
// Copy alignment from active gyro, as all production boards use acc-gyro-combi chip.
// Exceptions are STM32F3DISCOVERY and STM32F411DISCOVERY, and (may be) handled in future enhancement.
acc.dev.accAlign = gyroDeviceConfig(0)->align;
sensor_align_e alignment = gyroDeviceConfig(0)->alignment;
const sensorAlignment_t* customAlignment = &gyroDeviceConfig(0)->customAlignment;
#ifdef USE_MULTI_GYRO
if (gyroConfig()->gyro_to_use == GYRO_CONFIG_USE_GYRO_2) {
acc.dev.accAlign = gyroDeviceConfig(1)->align;
alignment = gyroDeviceConfig(1)->alignment;
customAlignment = &gyroDeviceConfig(1)->customAlignment;
}
#endif
acc.dev.accAlign = alignment;
buildRotationMatrixFromAlignment(customAlignment, &acc.dev.rotationMatrix);
if (!accDetect(&acc.dev, accelerometerConfig()->acc_hardware)) {
return false;
@ -485,7 +491,11 @@ void accUpdate(timeUs_t currentTimeUs, rollAndPitchTrims_t *rollAndPitchTrims)
}
}
alignSensors(acc.accADC, acc.dev.accAlign);
if (acc.dev.accAlign == ALIGN_CUSTOM) {
alignSensorViaMatrix(acc.accADC, &acc.dev.rotationMatrix);
} else {
alignSensorViaRotation(acc.accADC, acc.dev.accAlign);
}
if (!accIsCalibrationComplete()) {
performAcclerationCalibration(rollAndPitchTrims);