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"
26 #include "common/vector.h"
31 extern bool canUseGPSHeading
;
39 #define QUATERNION_INITIALIZE {.w=1, .x=0, .y=0,.z=0}
42 float ww
,wx
,wy
,wz
,xx
,xy
,xz
,yy
,yz
,zz
;
44 #define QUATERNION_PRODUCTS_INITIALIZE {.ww=1, .wx=0, .wy=0, .wz=0, .xx=0, .xy=0, .xz=0, .yy=0, .yz=0, .zz=0}
47 int16_t raw
[XYZ_AXIS_COUNT
];
49 // absolute angle inclination in multiple of 0.1 degree eg attitude.values.yaw 180 deg = 1800
54 } attitudeEulerAngles_t
;
55 #define EULER_INITIALIZE { { 0, 0, 0 } }
57 extern attitudeEulerAngles_t attitude
;
58 extern matrix33_t rMat
;
59 extern quaternion_t imuAttitudeQuaternion
; //attitude quaternion to use in blackbox
61 typedef struct imuConfig_s
{
62 uint16_t imu_dcm_kp
; // DCM filter proportional gain ( x 10000)
63 uint16_t imu_dcm_ki
; // DCM filter integral gain ( x 10000)
65 uint8_t imu_process_denom
;
66 uint16_t mag_declination
; // Magnetic declination in degrees * 10
69 PG_DECLARE(imuConfig_t
, imuConfig
);
71 typedef struct imuRuntimeConfig_s
{
76 void imuConfigure(uint16_t throttle_correction_angle
, uint8_t throttle_correction_value
);
78 float getSinPitchAngle(void);
79 float getCosTiltAngle(void);
80 void getQuaternion(quaternion_t
* q
);
81 void imuUpdateAttitude(timeUs_t currentTimeUs
);
85 #ifdef SIMULATOR_BUILD
86 void imuSetAttitudeRPY(float roll
, float pitch
, float yaw
); // in deg
87 void imuSetAttitudeQuat(float w
, float x
, float y
, float z
);
88 #if defined(SIMULATOR_IMU_SYNC)
89 void imuSetHasNewData(uint32_t dt
);
93 bool imuQuaternionHeadfreeOffsetSet(void);
94 void imuQuaternionHeadfreeTransformVectorEarthToBody(vector3_t
*v
);
95 bool shouldInitializeGPSHeading(void);