1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 16:25:31 +03:00
betaflight/src/test/unit/sensor_gyro_unittest.cc
Dominic Clifton 980df1536f 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.
2019-07-13 11:51:20 +12:00

163 lines
5.1 KiB
C++

/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <stdbool.h>
#include <limits.h>
#include <algorithm>
extern "C" {
#include <platform.h>
#include "build/build_config.h"
#include "build/debug.h"
#include "common/axis.h"
#include "common/maths.h"
#include "common/utils.h"
#include "drivers/accgyro/accgyro_fake.h"
#include "drivers/accgyro/accgyro_mpu.h"
#include "drivers/sensor.h"
#include "io/beeper.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "scheduler/scheduler.h"
#include "sensors/gyro.h"
#include "sensors/acceleration.h"
#include "sensors/sensors.h"
STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev);
struct gyroSensor_s;
STATIC_UNIT_TESTED void performGyroCalibration(struct gyroSensor_s *gyroSensor, uint8_t gyroMovementCalibrationThreshold);
STATIC_UNIT_TESTED bool fakeGyroRead(gyroDev_t *gyro);
uint8_t debugMode;
int16_t debug[DEBUG16_VALUE_COUNT];
}
#include "unittest_macros.h"
#include "gtest/gtest.h"
extern gyroSensor_s * const gyroSensorPtr;
extern gyroDev_t * const gyroDevPtr;
TEST(SensorGyro, Detect)
{
const gyroHardware_e detected = gyroDetect(gyroDevPtr);
EXPECT_EQ(GYRO_FAKE, detected);
}
TEST(SensorGyro, Init)
{
pgResetAll();
const bool initialised = gyroInit();
EXPECT_EQ(true, initialised);
EXPECT_EQ(GYRO_FAKE, detectedSensors[SENSOR_INDEX_GYRO]);
}
TEST(SensorGyro, Read)
{
pgResetAll();
gyroInit();
fakeGyroSet(gyroDevPtr, 5, 6, 7);
const bool read = gyroDevPtr->readFn(gyroDevPtr);
EXPECT_EQ(true, read);
EXPECT_EQ(5, gyroDevPtr->gyroADCRaw[X]);
EXPECT_EQ(6, gyroDevPtr->gyroADCRaw[Y]);
EXPECT_EQ(7, gyroDevPtr->gyroADCRaw[Z]);
}
TEST(SensorGyro, Calibrate)
{
pgResetAll();
gyroInit();
fakeGyroSet(gyroDevPtr, 5, 6, 7);
const bool read = gyroDevPtr->readFn(gyroDevPtr);
EXPECT_EQ(true, read);
EXPECT_EQ(5, gyroDevPtr->gyroADCRaw[X]);
EXPECT_EQ(6, gyroDevPtr->gyroADCRaw[Y]);
EXPECT_EQ(7, gyroDevPtr->gyroADCRaw[Z]);
static const int gyroMovementCalibrationThreshold = 32;
gyroDevPtr->gyroZero[X] = 8;
gyroDevPtr->gyroZero[Y] = 9;
gyroDevPtr->gyroZero[Z] = 10;
performGyroCalibration(gyroSensorPtr, gyroMovementCalibrationThreshold);
EXPECT_EQ(8, gyroDevPtr->gyroZero[X]);
EXPECT_EQ(9, gyroDevPtr->gyroZero[Y]);
EXPECT_EQ(10, gyroDevPtr->gyroZero[Z]);
gyroStartCalibration(false);
EXPECT_EQ(false, isGyroCalibrationComplete());
while (!isGyroCalibrationComplete()) {
gyroDevPtr->readFn(gyroDevPtr);
performGyroCalibration(gyroSensorPtr, gyroMovementCalibrationThreshold);
}
EXPECT_EQ(5, gyroDevPtr->gyroZero[X]);
EXPECT_EQ(6, gyroDevPtr->gyroZero[Y]);
EXPECT_EQ(7, gyroDevPtr->gyroZero[Z]);
}
TEST(SensorGyro, Update)
{
pgResetAll();
// turn off filters
gyroConfigMutable()->gyro_lowpass_hz = 0;
gyroConfigMutable()->gyro_lowpass2_hz = 0;
gyroConfigMutable()->gyro_soft_notch_hz_1 = 0;
gyroConfigMutable()->gyro_soft_notch_hz_2 = 0;
gyroInit();
gyroDevPtr->readFn = fakeGyroRead;
gyroStartCalibration(false);
EXPECT_EQ(false, isGyroCalibrationComplete());
timeUs_t currentTimeUs = 0;
fakeGyroSet(gyroDevPtr, 5, 6, 7);
gyroUpdate(currentTimeUs);
while (!isGyroCalibrationComplete()) {
fakeGyroSet(gyroDevPtr, 5, 6, 7);
gyroUpdate(currentTimeUs);
}
EXPECT_EQ(true, isGyroCalibrationComplete());
EXPECT_EQ(5, gyroDevPtr->gyroZero[X]);
EXPECT_EQ(6, gyroDevPtr->gyroZero[Y]);
EXPECT_EQ(7, gyroDevPtr->gyroZero[Z]);
EXPECT_FLOAT_EQ(0, gyro.gyroADCf[X]);
EXPECT_FLOAT_EQ(0, gyro.gyroADCf[Y]);
EXPECT_FLOAT_EQ(0, gyro.gyroADCf[Z]);
gyroUpdate(currentTimeUs);
// expect zero values since gyro is calibrated
EXPECT_FLOAT_EQ(0, gyro.gyroADCf[X]);
EXPECT_FLOAT_EQ(0, gyro.gyroADCf[Y]);
EXPECT_FLOAT_EQ(0, gyro.gyroADCf[Z]);
fakeGyroSet(gyroDevPtr, 15, 26, 97);
gyroUpdate(currentTimeUs);
EXPECT_NEAR(10 * gyroDevPtr->scale, gyro.gyroADCf[X], 1e-3); // gyroADCf values are scaled
EXPECT_NEAR(20 * gyroDevPtr->scale, gyro.gyroADCf[Y], 1e-3);
EXPECT_NEAR(90 * gyroDevPtr->scale, gyro.gyroADCf[Z], 1e-3);
}
// STUBS
extern "C" {
uint32_t micros(void) {return 0;}
void beeper(beeperMode_e) {}
uint8_t detectedSensors[] = { GYRO_NONE, ACC_NONE };
timeDelta_t getGyroUpdateRate(void) {return gyro.targetLooptime;}
void sensorsSet(uint32_t) {}
void schedulerResetTaskStatistics(cfTaskId_e) {}
int getArmingDisableFlags(void) {return 0;}
}