Paparazzi UAS  v5.18.0_stable
Paparazzi is a free software Unmanned Aircraft System.
imu.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2008-2009 Antoine Drouin <poinix@gmail.com>
3  *
4  * This file is part of paparazzi.
5  *
6  * paparazzi is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2, or (at your option)
9  * any later version.
10  *
11  * paparazzi is distributed in the hope that it will be useful,
12  * but WITHOUT ANY WARRANTY; without even the implied warranty of
13  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14  * GNU General Public License for more details.
15  *
16  * You should have received a copy of the GNU General Public License
17  * along with paparazzi; see the file COPYING. If not, write to
18  * the Free Software Foundation, 59 Temple Place - Suite 330,
19  * Boston, MA 02111-1307, USA.
20  */
21 
27 #ifndef IMU_H
28 #define IMU_H
29 
30 #include "math/pprz_algebra_int.h"
33 #include "generated/airframe.h"
34 
35 
37 struct Imu {
38  struct Int32Rates gyro;
39  struct Int32Vect3 accel;
40  struct Int32Vect3 mag;
50 
55 };
56 
58 extern struct Imu imu;
59 
60 /* underlying hardware */
61 #ifdef IMU_TYPE_H
62 #include IMU_TYPE_H
63 #endif
64 
65 extern void imu_init(void);
66 extern void imu_SetBodyToImuPhi(float phi);
67 extern void imu_SetBodyToImuTheta(float theta);
68 extern void imu_SetBodyToImuPsi(float psi);
69 extern void imu_SetBodyToImuCurrent(float set);
70 extern void imu_ResetBodyToImu(float reset);
71 
72 /* can be provided implementation */
73 extern void imu_scale_gyro(struct Imu *_imu);
74 extern void imu_scale_accel(struct Imu *_imu);
75 extern void imu_scale_mag(struct Imu *_imu);
76 
77 #if !defined IMU_BODY_TO_IMU_PHI && !defined IMU_BODY_TO_IMU_THETA && !defined IMU_BODY_TO_IMU_PSI
78 #define IMU_BODY_TO_IMU_PHI 0
79 #define IMU_BODY_TO_IMU_THETA 0
80 #define IMU_BODY_TO_IMU_PSI 0
81 #endif
82 
83 #if !defined IMU_GYRO_P_NEUTRAL && !defined IMU_GYRO_Q_NEUTRAL && !defined IMU_GYRO_R_NEUTRAL
84 #define IMU_GYRO_P_NEUTRAL 0
85 #define IMU_GYRO_Q_NEUTRAL 0
86 #define IMU_GYRO_R_NEUTRAL 0
87 #endif
88 
89 #if !defined IMU_ACCEL_X_NEUTRAL && !defined IMU_ACCEL_Y_NEUTRAL && !defined IMU_ACCEL_Z_NEUTRAL
90 #define IMU_ACCEL_X_NEUTRAL 0
91 #define IMU_ACCEL_Y_NEUTRAL 0
92 #define IMU_ACCEL_Z_NEUTRAL 0
93 #endif
94 
95 #if !defined IMU_MAG_X_NEUTRAL && !defined IMU_MAG_Y_NEUTRAL && !defined IMU_MAG_Z_NEUTRAL
96 #define IMU_MAG_X_NEUTRAL 0
97 #define IMU_MAG_Y_NEUTRAL 0
98 #define IMU_MAG_Z_NEUTRAL 0
99 #endif
100 
101 #if !defined IMU_GYRO_P_SIGN & !defined IMU_GYRO_Q_SIGN & !defined IMU_GYRO_R_SIGN
102 #define IMU_GYRO_P_SIGN 1
103 #define IMU_GYRO_Q_SIGN 1
104 #define IMU_GYRO_R_SIGN 1
105 #endif
106 #if !defined IMU_ACCEL_X_SIGN & !defined IMU_ACCEL_Y_SIGN & !defined IMU_ACCEL_Z_SIGN
107 #define IMU_ACCEL_X_SIGN 1
108 #define IMU_ACCEL_Y_SIGN 1
109 #define IMU_ACCEL_Z_SIGN 1
110 #endif
111 #if !defined IMU_MAG_X_SIGN & !defined IMU_MAG_Y_SIGN & !defined IMU_MAG_Z_SIGN
112 #define IMU_MAG_X_SIGN 1
113 #define IMU_MAG_Y_SIGN 1
114 #define IMU_MAG_Z_SIGN 1
115 #endif
116 
117 
118 #endif /* IMU_H */
Imu::gyro_unscaled
struct Int32Rates gyro_unscaled
unscaled gyroscope measurements
Definition: imu.h:46
OrientationReps
Definition: pprz_orientation_conversion.h:79
imu_scale_accel
void imu_scale_accel(struct Imu *_imu)
Definition: imu_vectornav.c:44
Int32Rates
angular rates
Definition: pprz_algebra_int.h:179
Imu::accel
struct Int32Vect3 accel
accelerometer measurements in m/s^2 in BFP with INT32_ACCEL_FRAC
Definition: imu.h:39
imu_SetBodyToImuPhi
void imu_SetBodyToImuPhi(float phi)
Definition: imu.c:151
Imu::b2i_set_current
bool b2i_set_current
flag for adjusting body_to_imu via settings.
Definition: imu.h:54
Imu::mag_neutral
struct Int32Vect3 mag_neutral
magnetometer neutral readings (bias) in raw/unscaled units
Definition: imu.h:45
Imu::body_to_imu
struct OrientationReps body_to_imu
rotation from body to imu frame
Definition: imu.h:49
imu_SetBodyToImuCurrent
void imu_SetBodyToImuCurrent(float set)
Definition: imu.c:178
pprz_algebra_float.h
Paparazzi floating point algebra.
imu_SetBodyToImuPsi
void imu_SetBodyToImuPsi(float psi)
Definition: imu.c:169
pprz_algebra_int.h
Paparazzi fixed point algebra.
Imu::accel_unscaled
struct Int32Vect3 accel_unscaled
unscaled accelerometer measurements
Definition: imu.h:47
Imu
abstract IMU interface providing fixed point interface
Definition: imu.h:37
imu
struct Imu imu
global IMU state
Definition: imu.c:108
Int32Vect3
Definition: pprz_algebra_int.h:88
Imu::gyro_neutral
struct Int32Rates gyro_neutral
static gyroscope bias from calibration in raw/unscaled units
Definition: imu.h:43
Imu::accel_neutral
struct Int32Vect3 accel_neutral
static accelerometer bias from calibration in raw/unscaled units
Definition: imu.h:44
imu_scale_gyro
void imu_scale_gyro(struct Imu *_imu)
Definition: imu_vectornav.c:43
imu_init
void imu_init(void)
Definition: imu.c:110
reset
void reset(void)
pprz_orientation_conversion.h
imu_SetBodyToImuTheta
void imu_SetBodyToImuTheta(float theta)
Definition: imu.c:160
Imu::accel_prev
struct Int32Vect3 accel_prev
previous accelerometer measurements
Definition: imu.h:42
Imu::mag
struct Int32Vect3 mag
magnetometer measurements scaled to 1 in BFP with INT32_MAG_FRAC
Definition: imu.h:40
Imu::mag_unscaled
struct Int32Vect3 mag_unscaled
unscaled magnetometer measurements
Definition: imu.h:48
imu_ResetBodyToImu
void imu_ResetBodyToImu(float reset)
imu_scale_mag
void imu_scale_mag(struct Imu *_imu)
Definition: ahrs_gx3.c:352
Imu::gyro_prev
struct Int32Rates gyro_prev
previous gyroscope measurements
Definition: imu.h:41
Imu::gyro
struct Int32Rates gyro
gyroscope measurements in rad/s in BFP with INT32_RATE_FRAC
Definition: imu.h:38