mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 00:35:39 +03:00
need implement fake eeprom & fake IO need implement fake system function can compile, stuck in isEEPROMContentValid() EEPROM in memory work EEPROM as file should work fix some complie warning MSP over TCP work (add dyad.c) a little clean up fix FLASH_CONFIG_Size in ld script & implement some pwmout IO to simulator work!! need to check direction & scale!! can fly but Gyro buggy move dyad.c fix busy-loop (limit to max 20kHz) can simulatie in different speed now! (hard code) add option for IMU calculation add README.md move dyad.c and fix F3 overrun the flash size explanation SITL in README.md and reuse CFLAGS, ASFLAGS
466 lines
14 KiB
C
466 lines
14 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/>.
|
|
*/
|
|
|
|
// Inertial Measurement Unit (IMU)
|
|
|
|
#include <stdbool.h>
|
|
#include <stdint.h>
|
|
#include <math.h>
|
|
|
|
#include "platform.h"
|
|
|
|
#include "build/build_config.h"
|
|
#include "build/debug.h"
|
|
|
|
#include "common/axis.h"
|
|
#include "common/maths.h"
|
|
|
|
#include "config/parameter_group.h"
|
|
#include "config/parameter_group_ids.h"
|
|
|
|
#include "drivers/system.h"
|
|
|
|
#include "fc/runtime_config.h"
|
|
|
|
#include "flight/imu.h"
|
|
#include "flight/mixer.h"
|
|
#include "flight/pid.h"
|
|
|
|
#include "io/gps.h"
|
|
|
|
#include "sensors/acceleration.h"
|
|
#include "sensors/barometer.h"
|
|
#include "sensors/compass.h"
|
|
#include "sensors/gyro.h"
|
|
#include "sensors/sensors.h"
|
|
#include "sensors/sonar.h"
|
|
|
|
|
|
// the limit (in degrees/second) beyond which we stop integrating
|
|
// omega_I. At larger spin rates the DCM PI controller can get 'dizzy'
|
|
// which results in false gyro drift. See
|
|
// http://gentlenav.googlecode.com/files/fastRotations.pdf
|
|
|
|
#define SPIN_RATE_LIMIT 20
|
|
|
|
int32_t accSum[XYZ_AXIS_COUNT];
|
|
|
|
uint32_t accTimeSum = 0; // keep track for integration of acc
|
|
int accSumCount = 0;
|
|
float accVelScale;
|
|
|
|
static float throttleAngleScale;
|
|
static float fc_acc;
|
|
static float smallAngleCosZ = 0;
|
|
|
|
static float magneticDeclination = 0.0f; // calculated at startup from config
|
|
|
|
static imuRuntimeConfig_t imuRuntimeConfig;
|
|
|
|
STATIC_UNIT_TESTED float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f; // quaternion of sensor frame relative to earth frame
|
|
static float rMat[3][3];
|
|
|
|
attitudeEulerAngles_t attitude = { { 0, 0, 0 } }; // absolute angle inclination in multiple of 0.1 degree 180 deg = 1800
|
|
|
|
PG_REGISTER_WITH_RESET_TEMPLATE(imuConfig_t, imuConfig, PG_IMU_CONFIG, 0);
|
|
|
|
PG_RESET_TEMPLATE(imuConfig_t, imuConfig,
|
|
.dcm_kp = 2500, // 1.0 * 10000
|
|
.dcm_ki = 0, // 0.003 * 10000
|
|
.small_angle = 25,
|
|
.accDeadband = {.xy = 40, .z= 40},
|
|
.acc_unarmedcal = 1
|
|
);
|
|
|
|
STATIC_UNIT_TESTED void imuComputeRotationMatrix(void)
|
|
{
|
|
float q1q1 = sq(q1);
|
|
float q2q2 = sq(q2);
|
|
float q3q3 = sq(q3);
|
|
|
|
float q0q1 = q0 * q1;
|
|
float q0q2 = q0 * q2;
|
|
float q0q3 = q0 * q3;
|
|
float q1q2 = q1 * q2;
|
|
float q1q3 = q1 * q3;
|
|
float q2q3 = q2 * q3;
|
|
|
|
rMat[0][0] = 1.0f - 2.0f * q2q2 - 2.0f * q3q3;
|
|
rMat[0][1] = 2.0f * (q1q2 + -q0q3);
|
|
rMat[0][2] = 2.0f * (q1q3 - -q0q2);
|
|
|
|
rMat[1][0] = 2.0f * (q1q2 - -q0q3);
|
|
rMat[1][1] = 1.0f - 2.0f * q1q1 - 2.0f * q3q3;
|
|
rMat[1][2] = 2.0f * (q2q3 + -q0q1);
|
|
|
|
rMat[2][0] = 2.0f * (q1q3 + -q0q2);
|
|
rMat[2][1] = 2.0f * (q2q3 - -q0q1);
|
|
rMat[2][2] = 1.0f - 2.0f * q1q1 - 2.0f * q2q2;
|
|
}
|
|
|
|
/*
|
|
* Calculate RC time constant used in the accZ lpf.
|
|
*/
|
|
static float calculateAccZLowPassFilterRCTimeConstant(float accz_lpf_cutoff)
|
|
{
|
|
return 0.5f / (M_PIf * accz_lpf_cutoff);
|
|
}
|
|
|
|
static float calculateThrottleAngleScale(uint16_t throttle_correction_angle)
|
|
{
|
|
return (1800.0f / M_PIf) * (900.0f / throttle_correction_angle);
|
|
}
|
|
|
|
void imuConfigure(uint16_t throttle_correction_angle)
|
|
{
|
|
imuRuntimeConfig.dcm_kp = imuConfig()->dcm_kp / 10000.0f;
|
|
imuRuntimeConfig.dcm_ki = imuConfig()->dcm_ki / 10000.0f;
|
|
imuRuntimeConfig.acc_unarmedcal = imuConfig()->acc_unarmedcal;
|
|
imuRuntimeConfig.small_angle = imuConfig()->small_angle;
|
|
|
|
fc_acc = calculateAccZLowPassFilterRCTimeConstant(5.0f); // Set to fix value
|
|
throttleAngleScale = calculateThrottleAngleScale(throttle_correction_angle);
|
|
}
|
|
|
|
void imuInit(void)
|
|
{
|
|
smallAngleCosZ = cos_approx(degreesToRadians(imuRuntimeConfig.small_angle));
|
|
accVelScale = 9.80665f / acc.dev.acc_1G / 10000.0f;
|
|
|
|
imuComputeRotationMatrix();
|
|
}
|
|
|
|
void imuResetAccelerationSum(void)
|
|
{
|
|
accSum[0] = 0;
|
|
accSum[1] = 0;
|
|
accSum[2] = 0;
|
|
accSumCount = 0;
|
|
accTimeSum = 0;
|
|
}
|
|
|
|
static void imuTransformVectorBodyToEarth(t_fp_vector * v)
|
|
{
|
|
/* From body frame to earth frame */
|
|
const float x = rMat[0][0] * v->V.X + rMat[0][1] * v->V.Y + rMat[0][2] * v->V.Z;
|
|
const float y = rMat[1][0] * v->V.X + rMat[1][1] * v->V.Y + rMat[1][2] * v->V.Z;
|
|
const float z = rMat[2][0] * v->V.X + rMat[2][1] * v->V.Y + rMat[2][2] * v->V.Z;
|
|
|
|
v->V.X = x;
|
|
v->V.Y = -y;
|
|
v->V.Z = z;
|
|
}
|
|
|
|
// rotate acc into Earth frame and calculate acceleration in it
|
|
static void imuCalculateAcceleration(uint32_t deltaT)
|
|
{
|
|
static int32_t accZoffset = 0;
|
|
static float accz_smooth = 0;
|
|
|
|
// deltaT is measured in us ticks
|
|
const float dT = (float)deltaT * 1e-6f;
|
|
|
|
t_fp_vector accel_ned;
|
|
accel_ned.V.X = acc.accSmooth[X];
|
|
accel_ned.V.Y = acc.accSmooth[Y];
|
|
accel_ned.V.Z = acc.accSmooth[Z];
|
|
|
|
imuTransformVectorBodyToEarth(&accel_ned);
|
|
|
|
if (imuRuntimeConfig.acc_unarmedcal == 1) {
|
|
if (!ARMING_FLAG(ARMED)) {
|
|
accZoffset -= accZoffset / 64;
|
|
accZoffset += accel_ned.V.Z;
|
|
}
|
|
accel_ned.V.Z -= accZoffset / 64; // compensate for gravitation on z-axis
|
|
} else {
|
|
accel_ned.V.Z -= acc.dev.acc_1G;
|
|
}
|
|
|
|
accz_smooth = accz_smooth + (dT / (fc_acc + dT)) * (accel_ned.V.Z - accz_smooth); // low pass filter
|
|
|
|
// apply Deadband to reduce integration drift and vibration influence
|
|
accSum[X] += applyDeadband(lrintf(accel_ned.V.X), imuRuntimeConfig.accDeadband.xy);
|
|
accSum[Y] += applyDeadband(lrintf(accel_ned.V.Y), imuRuntimeConfig.accDeadband.xy);
|
|
accSum[Z] += applyDeadband(lrintf(accz_smooth), imuRuntimeConfig.accDeadband.z);
|
|
|
|
// sum up Values for later integration to get velocity and distance
|
|
accTimeSum += deltaT;
|
|
accSumCount++;
|
|
}
|
|
|
|
static float invSqrt(float x)
|
|
{
|
|
return 1.0f / sqrtf(x);
|
|
}
|
|
|
|
static bool imuUseFastGains(void)
|
|
{
|
|
return !ARMING_FLAG(ARMED) && millis() < 20000;
|
|
}
|
|
|
|
static float imuGetPGainScaleFactor(void)
|
|
{
|
|
if (imuUseFastGains()) {
|
|
return 10.0f;
|
|
}
|
|
else {
|
|
return 1.0f;
|
|
}
|
|
}
|
|
|
|
static void imuMahonyAHRSupdate(float dt, float gx, float gy, float gz,
|
|
bool useAcc, float ax, float ay, float az,
|
|
bool useMag, float mx, float my, float mz,
|
|
bool useYaw, float yawError)
|
|
{
|
|
static float integralFBx = 0.0f, integralFBy = 0.0f, integralFBz = 0.0f; // integral error terms scaled by Ki
|
|
|
|
// Calculate general spin rate (rad/s)
|
|
const float spin_rate = sqrtf(sq(gx) + sq(gy) + sq(gz));
|
|
|
|
// Use raw heading error (from GPS or whatever else)
|
|
float ez = 0;
|
|
if (useYaw) {
|
|
while (yawError > M_PIf) yawError -= (2.0f * M_PIf);
|
|
while (yawError < -M_PIf) yawError += (2.0f * M_PIf);
|
|
|
|
ez += sin_approx(yawError / 2.0f);
|
|
}
|
|
|
|
// Use measured magnetic field vector
|
|
float ex = 0, ey = 0;
|
|
float recipNorm = sq(mx) + sq(my) + sq(mz);
|
|
if (useMag && recipNorm > 0.01f) {
|
|
// Normalise magnetometer measurement
|
|
recipNorm = invSqrt(recipNorm);
|
|
mx *= recipNorm;
|
|
my *= recipNorm;
|
|
mz *= recipNorm;
|
|
|
|
// For magnetometer correction we make an assumption that magnetic field is perpendicular to gravity (ignore Z-component in EF).
|
|
// This way magnetic field will only affect heading and wont mess roll/pitch angles
|
|
|
|
// (hx; hy; 0) - measured mag field vector in EF (assuming Z-component is zero)
|
|
// (bx; 0; 0) - reference mag field vector heading due North in EF (assuming Z-component is zero)
|
|
const float hx = rMat[0][0] * mx + rMat[0][1] * my + rMat[0][2] * mz;
|
|
const float hy = rMat[1][0] * mx + rMat[1][1] * my + rMat[1][2] * mz;
|
|
const float bx = sqrtf(hx * hx + hy * hy);
|
|
|
|
// magnetometer error is cross product between estimated magnetic north and measured magnetic north (calculated in EF)
|
|
const float ez_ef = -(hy * bx);
|
|
|
|
// Rotate mag error vector back to BF and accumulate
|
|
ex += rMat[2][0] * ez_ef;
|
|
ey += rMat[2][1] * ez_ef;
|
|
ez += rMat[2][2] * ez_ef;
|
|
}
|
|
|
|
// Use measured acceleration vector
|
|
recipNorm = sq(ax) + sq(ay) + sq(az);
|
|
if (useAcc && recipNorm > 0.01f) {
|
|
// Normalise accelerometer measurement
|
|
recipNorm = invSqrt(recipNorm);
|
|
ax *= recipNorm;
|
|
ay *= recipNorm;
|
|
az *= recipNorm;
|
|
|
|
// Error is sum of cross product between estimated direction and measured direction of gravity
|
|
ex += (ay * rMat[2][2] - az * rMat[2][1]);
|
|
ey += (az * rMat[2][0] - ax * rMat[2][2]);
|
|
ez += (ax * rMat[2][1] - ay * rMat[2][0]);
|
|
}
|
|
|
|
// Compute and apply integral feedback if enabled
|
|
if(imuRuntimeConfig.dcm_ki > 0.0f) {
|
|
// Stop integrating if spinning beyond the certain limit
|
|
if (spin_rate < DEGREES_TO_RADIANS(SPIN_RATE_LIMIT)) {
|
|
const float dcmKiGain = imuRuntimeConfig.dcm_ki;
|
|
integralFBx += dcmKiGain * ex * dt; // integral error scaled by Ki
|
|
integralFBy += dcmKiGain * ey * dt;
|
|
integralFBz += dcmKiGain * ez * dt;
|
|
}
|
|
}
|
|
else {
|
|
integralFBx = 0.0f; // prevent integral windup
|
|
integralFBy = 0.0f;
|
|
integralFBz = 0.0f;
|
|
}
|
|
|
|
// Calculate kP gain. If we are acquiring initial attitude (not armed and within 20 sec from powerup) scale the kP to converge faster
|
|
const float dcmKpGain = imuRuntimeConfig.dcm_kp * imuGetPGainScaleFactor();
|
|
|
|
// Apply proportional and integral feedback
|
|
gx += dcmKpGain * ex + integralFBx;
|
|
gy += dcmKpGain * ey + integralFBy;
|
|
gz += dcmKpGain * ez + integralFBz;
|
|
|
|
// Integrate rate of change of quaternion
|
|
gx *= (0.5f * dt);
|
|
gy *= (0.5f * dt);
|
|
gz *= (0.5f * dt);
|
|
|
|
const float qa = q0;
|
|
const float qb = q1;
|
|
const float qc = q2;
|
|
q0 += (-qb * gx - qc * gy - q3 * gz);
|
|
q1 += (qa * gx + qc * gz - q3 * gy);
|
|
q2 += (qa * gy - qb * gz + q3 * gx);
|
|
q3 += (qa * gz + qb * gy - qc * gx);
|
|
|
|
// Normalise quaternion
|
|
recipNorm = invSqrt(sq(q0) + sq(q1) + sq(q2) + sq(q3));
|
|
q0 *= recipNorm;
|
|
q1 *= recipNorm;
|
|
q2 *= recipNorm;
|
|
q3 *= recipNorm;
|
|
|
|
// Pre-compute rotation matrix from quaternion
|
|
imuComputeRotationMatrix();
|
|
}
|
|
|
|
STATIC_UNIT_TESTED void imuUpdateEulerAngles(void)
|
|
{
|
|
/* Compute pitch/roll angles */
|
|
attitude.values.roll = lrintf(atan2f(rMat[2][1], rMat[2][2]) * (1800.0f / M_PIf));
|
|
attitude.values.pitch = lrintf(((0.5f * M_PIf) - acosf(-rMat[2][0])) * (1800.0f / M_PIf));
|
|
attitude.values.yaw = lrintf((-atan2f(rMat[1][0], rMat[0][0]) * (1800.0f / M_PIf) + magneticDeclination));
|
|
|
|
if (attitude.values.yaw < 0)
|
|
attitude.values.yaw += 3600;
|
|
|
|
/* Update small angle state */
|
|
if (rMat[2][2] > smallAngleCosZ) {
|
|
ENABLE_STATE(SMALL_ANGLE);
|
|
} else {
|
|
DISABLE_STATE(SMALL_ANGLE);
|
|
}
|
|
}
|
|
|
|
static bool imuIsAccelerometerHealthy(void)
|
|
{
|
|
int32_t accMagnitude = 0;
|
|
for (int axis = 0; axis < 3; axis++) {
|
|
accMagnitude += (int32_t)acc.accSmooth[axis] * acc.accSmooth[axis];
|
|
}
|
|
|
|
accMagnitude = accMagnitude * 100 / (sq((int32_t)acc.dev.acc_1G));
|
|
|
|
// Accept accel readings only in range 0.90g - 1.10g
|
|
return (81 < accMagnitude) && (accMagnitude < 121);
|
|
}
|
|
|
|
static bool isMagnetometerHealthy(void)
|
|
{
|
|
return (mag.magADC[X] != 0) && (mag.magADC[Y] != 0) && (mag.magADC[Z] != 0);
|
|
}
|
|
|
|
static void imuCalculateEstimatedAttitude(timeUs_t currentTimeUs)
|
|
{
|
|
static uint32_t previousIMUUpdateTime;
|
|
float rawYawError = 0;
|
|
bool useAcc = false;
|
|
bool useMag = false;
|
|
bool useYaw = false;
|
|
|
|
uint32_t deltaT = currentTimeUs - previousIMUUpdateTime;
|
|
previousIMUUpdateTime = currentTimeUs;
|
|
|
|
if (imuIsAccelerometerHealthy()) {
|
|
useAcc = true;
|
|
}
|
|
|
|
if (sensors(SENSOR_MAG) && isMagnetometerHealthy()) {
|
|
useMag = true;
|
|
}
|
|
#if defined(GPS)
|
|
else if (STATE(FIXED_WING) && sensors(SENSOR_GPS) && STATE(GPS_FIX) && GPS_numSat >= 5 && GPS_speed >= 300) {
|
|
// In case of a fixed-wing aircraft we can use GPS course over ground to correct heading
|
|
rawYawError = DECIDEGREES_TO_RADIANS(attitude.values.yaw - GPS_ground_course);
|
|
useYaw = true;
|
|
}
|
|
#endif
|
|
|
|
#if defined(SIMULATOR_BUILD) && defined(SKIP_IMU_CALC)
|
|
UNUSED(imuMahonyAHRSupdate);
|
|
UNUSED(useAcc);
|
|
UNUSED(useMag);
|
|
UNUSED(useYaw);
|
|
UNUSED(rawYawError);
|
|
#else
|
|
imuMahonyAHRSupdate(deltaT * 1e-6f,
|
|
DEGREES_TO_RADIANS(gyro.gyroADCf[X]), DEGREES_TO_RADIANS(gyro.gyroADCf[Y]), DEGREES_TO_RADIANS(gyro.gyroADCf[Z]),
|
|
useAcc, acc.accSmooth[X], acc.accSmooth[Y], acc.accSmooth[Z],
|
|
useMag, mag.magADC[X], mag.magADC[Y], mag.magADC[Z],
|
|
useYaw, rawYawError);
|
|
|
|
imuUpdateEulerAngles();
|
|
#endif
|
|
imuCalculateAcceleration(deltaT); // rotate acc vector into earth frame
|
|
}
|
|
|
|
void imuUpdateAttitude(timeUs_t currentTimeUs)
|
|
{
|
|
if (sensors(SENSOR_ACC) && acc.isAccelUpdatedAtLeastOnce) {
|
|
imuCalculateEstimatedAttitude(currentTimeUs);
|
|
} else {
|
|
acc.accSmooth[X] = 0;
|
|
acc.accSmooth[Y] = 0;
|
|
acc.accSmooth[Z] = 0;
|
|
}
|
|
}
|
|
|
|
float getCosTiltAngle(void)
|
|
{
|
|
return rMat[2][2];
|
|
}
|
|
|
|
int16_t calculateThrottleAngleCorrection(uint8_t throttle_correction_value)
|
|
{
|
|
/*
|
|
* Use 0 as the throttle angle correction if we are inverted, vertical or with a
|
|
* small angle < 0.86 deg
|
|
* TODO: Define this small angle in config.
|
|
*/
|
|
if (rMat[2][2] <= 0.015f) {
|
|
return 0;
|
|
}
|
|
int angle = lrintf(acosf(rMat[2][2]) * throttleAngleScale);
|
|
if (angle > 900)
|
|
angle = 900;
|
|
return lrintf(throttle_correction_value * sin_approx(angle / (900.0f * M_PIf / 2.0f)));
|
|
}
|
|
|
|
#ifdef SIMULATOR_BUILD
|
|
void imuSetAttitudeRPY(float roll, float pitch, float yaw)
|
|
{
|
|
attitude.values.roll = roll * 10;
|
|
attitude.values.pitch = pitch * 10;
|
|
attitude.values.yaw = yaw * 10;
|
|
}
|
|
void imuSetAttitudeQuat(float w, float x, float y, float z)
|
|
{
|
|
q0 = w;
|
|
q1 = x;
|
|
q2 = y;
|
|
q3 = z;
|
|
|
|
imuComputeRotationMatrix();
|
|
imuUpdateEulerAngles();
|
|
}
|
|
#endif
|
|
|