345 lines
11 KiB
C
345 lines
11 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 "common/maths.h"
|
|
|
|
#include <platform.h>
|
|
|
|
#include "common/axis.h"
|
|
|
|
#include "drivers/system.h"
|
|
#include "drivers/sensor.h"
|
|
#include "drivers/accgyro.h"
|
|
#include "drivers/compass.h"
|
|
|
|
#include "sensors/sensors.h"
|
|
#include "sensors/gyro.h"
|
|
#include "sensors/compass.h"
|
|
#include "sensors/acceleration.h"
|
|
#include "sensors/barometer.h"
|
|
#include "sensors/sonar.h"
|
|
|
|
#include "flight/mixer.h"
|
|
#include "flight/flight.h"
|
|
#include "flight/imu.h"
|
|
|
|
#include "config/runtime_config.h"
|
|
|
|
|
|
extern int16_t debug[4];
|
|
|
|
int16_t accSmooth[XYZ_AXIS_COUNT];
|
|
int32_t accSum[XYZ_AXIS_COUNT];
|
|
int16_t gyroData[FLIGHT_DYNAMICS_INDEX_COUNT] = { 0, 0, 0 };
|
|
|
|
uint32_t accTimeSum = 0; // keep track for integration of acc
|
|
int accSumCount = 0;
|
|
float accVelScale;
|
|
|
|
int16_t smallAngle = 0;
|
|
|
|
float throttleAngleScale;
|
|
float fc_acc;
|
|
|
|
float magneticDeclination = 0.0f; // calculated at startup from config
|
|
float gyroScaleRad;
|
|
|
|
|
|
rollAndPitchInclination_t inclination = { { 0, 0 } }; // absolute angle inclination in multiple of 0.1 degree 180 deg = 1800
|
|
float anglerad[2] = { 0.0f, 0.0f }; // absolute angle inclination in radians
|
|
|
|
imuRuntimeConfig_t *imuRuntimeConfig;
|
|
pidProfile_t *pidProfile;
|
|
accDeadband_t *accDeadband;
|
|
|
|
void imuConfigure(
|
|
imuRuntimeConfig_t *initialImuRuntimeConfig,
|
|
pidProfile_t *initialPidProfile,
|
|
accDeadband_t *initialAccDeadband,
|
|
float accz_lpf_cutoff,
|
|
uint16_t throttle_correction_angle
|
|
)
|
|
{
|
|
imuRuntimeConfig = initialImuRuntimeConfig;
|
|
pidProfile = initialPidProfile;
|
|
accDeadband = initialAccDeadband;
|
|
fc_acc = calculateAccZLowPassFilterRCTimeConstant(accz_lpf_cutoff);
|
|
throttleAngleScale = calculateThrottleAngleScale(throttle_correction_angle);
|
|
}
|
|
|
|
void imuInit()
|
|
{
|
|
smallAngle = lrintf(acc_1G * cosf(degreesToRadians(imuRuntimeConfig->small_angle)));
|
|
accVelScale = 9.80665f / acc_1G / 10000.0f;
|
|
gyroScaleRad = gyro.scale * (M_PIf / 180.0f) * 0.000001f;
|
|
}
|
|
|
|
float calculateThrottleAngleScale(uint16_t throttle_correction_angle)
|
|
{
|
|
return (1800.0f / M_PIf) * (900.0f / throttle_correction_angle);
|
|
}
|
|
|
|
/*
|
|
* Calculate RC time constant used in the accZ lpf.
|
|
*/
|
|
float calculateAccZLowPassFilterRCTimeConstant(float accz_lpf_cutoff)
|
|
{
|
|
return 0.5f / (M_PIf * accz_lpf_cutoff);
|
|
}
|
|
|
|
// **************************************************
|
|
// Simplified IMU based on "Complementary Filter"
|
|
// Inspired by http://starlino.com/imu_guide.html
|
|
//
|
|
// adapted by ziss_dm : http://www.multiwii.com/forum/viewtopic.php?f=8&t=198
|
|
//
|
|
// The following ideas was used in this project:
|
|
// 1) Rotation matrix: http://en.wikipedia.org/wiki/Rotation_matrix
|
|
//
|
|
// Currently Magnetometer uses separate CF which is used only
|
|
// for heading approximation.
|
|
//
|
|
// **************************************************
|
|
|
|
|
|
t_fp_vector EstG;
|
|
|
|
void imuResetAccelerationSum(void)
|
|
{
|
|
accSum[0] = 0;
|
|
accSum[1] = 0;
|
|
accSum[2] = 0;
|
|
accSumCount = 0;
|
|
accTimeSum = 0;
|
|
}
|
|
|
|
// rotate acc into Earth frame and calculate acceleration in it
|
|
void imuCalculateAcceleration(uint32_t deltaT)
|
|
{
|
|
static int32_t accZoffset = 0;
|
|
static float accz_smooth = 0;
|
|
float dT;
|
|
fp_angles_t rpy;
|
|
t_fp_vector accel_ned;
|
|
|
|
// deltaT is measured in us ticks
|
|
dT = (float)deltaT * 1e-6f;
|
|
|
|
// the accel values have to be rotated into the earth frame
|
|
rpy.angles.roll = -(float)anglerad[AI_ROLL];
|
|
rpy.angles.pitch = -(float)anglerad[AI_PITCH];
|
|
rpy.angles.yaw = -(float)heading * RAD;
|
|
|
|
accel_ned.V.X = accSmooth[0];
|
|
accel_ned.V.Y = accSmooth[1];
|
|
accel_ned.V.Z = accSmooth[2];
|
|
|
|
rotateV(&accel_ned.V, &rpy);
|
|
|
|
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_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), accDeadband->xy);
|
|
accSum[Y] += applyDeadband(lrintf(accel_ned.V.Y), accDeadband->xy);
|
|
accSum[Z] += applyDeadband(lrintf(accz_smooth), accDeadband->z);
|
|
|
|
// sum up Values for later integration to get velocity and distance
|
|
accTimeSum += deltaT;
|
|
accSumCount++;
|
|
}
|
|
|
|
/*
|
|
* Baseflight calculation by Luggi09 originates from arducopter
|
|
* ============================================================
|
|
* This function rotates magnetic vector to cancel actual yaw and
|
|
* pitch of craft. Then it computes it's direction in X/Y plane.
|
|
* This value is returned as compass heading, value is 0-360 degrees.
|
|
*
|
|
* Note that Earth's magnetic field is not parallel with ground unless
|
|
* you are near equator. Its inclination is considerable, >60 degrees
|
|
* towards ground in most of Europe.
|
|
*
|
|
* First we consider it in 2D:
|
|
*
|
|
* An example, the vector <1, 1> would be turned into the heading
|
|
* 45 degrees, representing it's angle clockwise from north.
|
|
*
|
|
* ***************** *
|
|
* * | <1,1> *
|
|
* * | / *
|
|
* * | / *
|
|
* * |/ *
|
|
* * * *
|
|
* * *
|
|
* * *
|
|
* * *
|
|
* * *
|
|
* *******************
|
|
*
|
|
* //TODO: Add explanation for how it uses the Z dimension.
|
|
*/
|
|
int16_t imuCalculateHeading(t_fp_vector *vec)
|
|
{
|
|
int16_t head;
|
|
|
|
float cosineRoll = cosf(anglerad[AI_ROLL]);
|
|
float sineRoll = sinf(anglerad[AI_ROLL]);
|
|
float cosinePitch = cosf(anglerad[AI_PITCH]);
|
|
float sinePitch = sinf(anglerad[AI_PITCH]);
|
|
float Xh = vec->A[X] * cosinePitch + vec->A[Y] * sineRoll * sinePitch + vec->A[Z] * sinePitch * cosineRoll;
|
|
float Yh = vec->A[Y] * cosineRoll - vec->A[Z] * sineRoll;
|
|
//TODO: Replace this comment with an explanation of why Yh and Xh can never simultanoeusly be zero,
|
|
// or handle the case in which they are and (atan2f(0, 0) is undefined.
|
|
float hd = (atan2f(Yh, Xh) * 1800.0f / M_PIf + magneticDeclination) / 10.0f;
|
|
head = lrintf(hd);
|
|
|
|
// Arctan returns a value in the range -180 to 180 degrees. We 'normalize' negative angles to be positive.
|
|
if (head < 0)
|
|
head += 360;
|
|
|
|
return head;
|
|
}
|
|
|
|
static void imuCalculateEstimatedAttitude(void)
|
|
{
|
|
int32_t axis;
|
|
int32_t accMag = 0;
|
|
static t_fp_vector EstM;
|
|
static t_fp_vector EstN = { .A = { 1.0f, 0.0f, 0.0f } };
|
|
static float accLPF[3];
|
|
static uint32_t previousT;
|
|
uint32_t currentT = micros();
|
|
uint32_t deltaT;
|
|
float scale;
|
|
fp_angles_t deltaGyroAngle;
|
|
deltaT = currentT - previousT;
|
|
scale = deltaT * gyroScaleRad;
|
|
previousT = currentT;
|
|
|
|
// Initialization
|
|
for (axis = 0; axis < 3; axis++) {
|
|
deltaGyroAngle.raw[axis] = gyroADC[axis] * scale;
|
|
if (imuRuntimeConfig->acc_lpf_factor > 0) {
|
|
accLPF[axis] = accLPF[axis] * (1.0f - (1.0f / imuRuntimeConfig->acc_lpf_factor)) + accADC[axis] * (1.0f / imuRuntimeConfig->acc_lpf_factor);
|
|
accSmooth[axis] = accLPF[axis];
|
|
} else {
|
|
accSmooth[axis] = accADC[axis];
|
|
}
|
|
accMag += (int32_t)accSmooth[axis] * accSmooth[axis];
|
|
}
|
|
accMag = accMag * 100 / ((int32_t)acc_1G * acc_1G);
|
|
|
|
rotateV(&EstG.V, &deltaGyroAngle);
|
|
|
|
// Apply complimentary filter (Gyro drift correction)
|
|
// If accel magnitude >1.15G or <0.85G and ACC vector outside of the limit range => we neutralize the effect of accelerometers in the angle estimation.
|
|
// To do that, we just skip filter, as EstV already rotated by Gyro
|
|
|
|
float invGyroComplimentaryFilterFactor = (1.0f / (imuRuntimeConfig->gyro_cmpf_factor + 1.0f));
|
|
|
|
if (72 < (uint16_t)accMag && (uint16_t)accMag < 133) {
|
|
for (axis = 0; axis < 3; axis++)
|
|
EstG.A[axis] = (EstG.A[axis] * imuRuntimeConfig->gyro_cmpf_factor + accSmooth[axis]) * invGyroComplimentaryFilterFactor;
|
|
}
|
|
|
|
if (EstG.A[Z] > smallAngle) {
|
|
ENABLE_STATE(SMALL_ANGLE);
|
|
} else {
|
|
DISABLE_STATE(SMALL_ANGLE);
|
|
}
|
|
|
|
// Attitude of the estimated vector
|
|
anglerad[AI_ROLL] = atan2f(EstG.V.Y, EstG.V.Z);
|
|
anglerad[AI_PITCH] = atan2f(-EstG.V.X, sqrtf(EstG.V.Y * EstG.V.Y + EstG.V.Z * EstG.V.Z));
|
|
inclination.values.rollDeciDegrees = lrintf(anglerad[AI_ROLL] * (1800.0f / M_PIf));
|
|
inclination.values.pitchDeciDegrees = lrintf(anglerad[AI_PITCH] * (1800.0f / M_PIf));
|
|
|
|
if (sensors(SENSOR_MAG)) {
|
|
rotateV(&EstM.V, &deltaGyroAngle);
|
|
// FIXME what does the _M_ mean?
|
|
float invGyroComplimentaryFilter_M_Factor = (1.0f / (imuRuntimeConfig->gyro_cmpfm_factor + 1.0f));
|
|
for (axis = 0; axis < 3; axis++) {
|
|
EstM.A[axis] = (EstM.A[axis] * imuRuntimeConfig->gyro_cmpfm_factor + magADC[axis]) * invGyroComplimentaryFilter_M_Factor;
|
|
}
|
|
heading = imuCalculateHeading(&EstM);
|
|
} else {
|
|
rotateV(&EstN.V, &deltaGyroAngle);
|
|
normalizeV(&EstN.V, &EstN.V);
|
|
heading = imuCalculateHeading(&EstN);
|
|
}
|
|
|
|
imuCalculateAcceleration(deltaT); // rotate acc vector into earth frame
|
|
}
|
|
|
|
void imuUpdate(rollAndPitchTrims_t *accelerometerTrims, uint8_t mixerMode)
|
|
{
|
|
static int16_t gyroYawSmooth = 0;
|
|
|
|
gyroUpdate();
|
|
if (sensors(SENSOR_ACC)) {
|
|
updateAccelerationReadings(accelerometerTrims); // TODO rename to accelerometerUpdate and rename many other 'Acceleration' references to be 'Accelerometer'
|
|
imuCalculateEstimatedAttitude();
|
|
} else {
|
|
accADC[X] = 0;
|
|
accADC[Y] = 0;
|
|
accADC[Z] = 0;
|
|
}
|
|
|
|
gyroData[FD_ROLL] = gyroADC[FD_ROLL];
|
|
gyroData[FD_PITCH] = gyroADC[FD_PITCH];
|
|
|
|
if (mixerMode == MIXER_TRI) {
|
|
gyroData[FD_YAW] = (gyroYawSmooth * 2 + gyroADC[FD_YAW]) / 3;
|
|
gyroYawSmooth = gyroData[FD_YAW];
|
|
} else {
|
|
gyroData[FD_YAW] = gyroADC[FD_YAW];
|
|
}
|
|
}
|
|
|
|
int16_t calculateThrottleAngleCorrection(uint8_t throttle_correction_value)
|
|
{
|
|
float cosZ = EstG.V.Z / sqrtf(EstG.V.X * EstG.V.X + EstG.V.Y * EstG.V.Y + EstG.V.Z * EstG.V.Z);
|
|
|
|
/*
|
|
* 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 (cosZ <= 0.015f) {
|
|
return 0;
|
|
}
|
|
int angle = lrintf(acosf(cosZ) * throttleAngleScale);
|
|
if (angle > 900)
|
|
angle = 900;
|
|
return lrintf(throttle_correction_value * sinf(angle / (900.0f * M_PIf / 2.0f)));
|
|
}
|