2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
23 #include "common/axis.h"
24 #include "common/time.h"
25 #include "common/maths.h"
29 extern bool canUseGPSHeading
;
30 extern float accAverage
[XYZ_AXIS_COUNT
];
35 #define QUATERNION_INITIALIZE {.w=1, .x=0, .y=0,.z=0}
38 float ww
,wx
,wy
,wz
,xx
,xy
,xz
,yy
,yz
,zz
;
40 #define QUATERNION_PRODUCTS_INITIALIZE {.ww=1, .wx=0, .wy=0, .wz=0, .xx=0, .xy=0, .xz=0, .yy=0, .yz=0, .zz=0}
43 int16_t raw
[XYZ_AXIS_COUNT
];
45 // absolute angle inclination in multiple of 0.1 degree 180 deg = 1800
50 } attitudeEulerAngles_t
;
51 #define EULER_INITIALIZE { { 0, 0, 0 } }
53 extern attitudeEulerAngles_t attitude
;
54 extern float rMat
[3][3];
56 typedef struct imuConfig_s
{
57 uint16_t dcm_kp
; // DCM filter proportional gain ( x 10000)
58 uint16_t dcm_ki
; // DCM filter integral gain ( x 10000)
62 PG_DECLARE(imuConfig_t
, imuConfig
);
64 typedef struct imuRuntimeConfig_s
{
69 void imuConfigure(uint16_t throttle_correction_angle
, uint8_t throttle_correction_value
);
71 float getCosTiltAngle(void);
72 void getQuaternion(quaternion
* q
);
73 void imuUpdateAttitude(timeUs_t currentTimeUs
);
77 #ifdef SIMULATOR_BUILD
78 void imuSetAttitudeRPY(float roll
, float pitch
, float yaw
); // in deg
79 void imuSetAttitudeQuat(float w
, float x
, float y
, float z
);
80 #if defined(SIMULATOR_IMU_SYNC)
81 void imuSetHasNewData(uint32_t dt
);
85 bool imuQuaternionHeadfreeOffsetSet(void);
86 void imuQuaternionHeadfreeTransformVectorEarthToBody(t_fp_vector_def
* v
);
87 bool shouldInitializeGPSHeading(void);