1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 08:15:30 +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

@ -1368,41 +1368,41 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
sbufWriteU16(dst, flight3DConfig()->deadband3d_throttle);
break;
case MSP_SENSOR_ALIGNMENT: {
uint8_t gyroAlignment;
#ifdef USE_MULTI_GYRO
switch (gyroConfig()->gyro_to_use) {
case GYRO_CONFIG_USE_GYRO_2:
gyroAlignment = gyroDeviceConfig(1)->align;
gyroAlignment = gyroDeviceConfig(1)->alignment;
break;
case GYRO_CONFIG_USE_GYRO_BOTH:
// for dual-gyro in "BOTH" mode we only read/write gyro 0
default:
gyroAlignment = gyroDeviceConfig(0)->align;
gyroAlignment = gyroDeviceConfig(0)->alignment;
break;
}
#else
gyroAlignment = gyroDeviceConfig(0)->align;
gyroAlignment = gyroDeviceConfig(0)->alignment;
#endif
sbufWriteU8(dst, gyroAlignment);
sbufWriteU8(dst, gyroAlignment); // Starting with 4.0 gyro and acc alignment are the same
sbufWriteU8(dst, compassConfig()->mag_align);
sbufWriteU8(dst, compassConfig()->mag_alignment);
// API 1.41 - Add multi-gyro indicator, selected gyro, and support for separate gyro 1 & 2 alignment
sbufWriteU8(dst, getGyroDetectionFlags());
#ifdef USE_MULTI_GYRO
sbufWriteU8(dst, gyroConfig()->gyro_to_use);
sbufWriteU8(dst, gyroDeviceConfig(0)->align);
sbufWriteU8(dst, gyroDeviceConfig(1)->align);
sbufWriteU8(dst, gyroDeviceConfig(0)->alignment);
sbufWriteU8(dst, gyroDeviceConfig(1)->alignment);
#else
sbufWriteU8(dst, GYRO_CONFIG_USE_GYRO_1);
sbufWriteU8(dst, gyroDeviceConfig(0)->align);
sbufWriteU8(dst, gyroDeviceConfig(0)->alignment);
sbufWriteU8(dst, ALIGN_DEFAULT);
#endif
break;
}
case MSP_ADVANCED_CONFIG:
sbufWriteU8(dst, gyroConfig()->gyro_sync_denom);
sbufWriteU8(dst, pidConfig()->pid_process_denom);
@ -2007,21 +2007,22 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
case MSP_SET_RESET_CURR_PID:
resetPidProfile(currentPidProfile);
break;
case MSP_SET_SENSOR_ALIGNMENT: {
// maintain backwards compatibility for API < 1.41
const uint8_t gyroAlignment = sbufReadU8(src);
sbufReadU8(src); // discard deprecated acc_align
compassConfigMutable()->mag_align = sbufReadU8(src);
compassConfigMutable()->mag_alignment = sbufReadU8(src);
if (sbufBytesRemaining(src) >= 3) {
// API >= 1.41 - support the gyro_to_use and alignment for gyros 1 & 2
#ifdef USE_MULTI_GYRO
gyroConfigMutable()->gyro_to_use = sbufReadU8(src);
gyroDeviceConfigMutable(0)->align = sbufReadU8(src);
gyroDeviceConfigMutable(1)->align = sbufReadU8(src);
gyroDeviceConfigMutable(0)->alignment = sbufReadU8(src);
gyroDeviceConfigMutable(1)->alignment = sbufReadU8(src);
#else
sbufReadU8(src); // unused gyro_to_use
gyroDeviceConfigMutable(0)->align = sbufReadU8(src);
gyroDeviceConfigMutable(0)->alignment = sbufReadU8(src);
sbufReadU8(src); // unused gyro_2_sensor_align
#endif
} else {
@ -2029,16 +2030,16 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
#ifdef USE_MULTI_GYRO
switch (gyroConfig()->gyro_to_use) {
case GYRO_CONFIG_USE_GYRO_2:
gyroDeviceConfigMutable(1)->align = gyroAlignment;
gyroDeviceConfigMutable(1)->alignment = gyroAlignment;
break;
case GYRO_CONFIG_USE_GYRO_BOTH:
// For dual-gyro in "BOTH" mode we'll only update gyro 0
default:
gyroDeviceConfigMutable(0)->align = gyroAlignment;
gyroDeviceConfigMutable(0)->alignment = gyroAlignment;
break;
}
#else
gyroDeviceConfigMutable(0)->align = gyroAlignment;
gyroDeviceConfigMutable(0)->alignment = gyroAlignment;
#endif
}