Paparazzi UAS  v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
imu.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2008-2022 The Paparazzi Team
3  * Freek van Tienen <freek.v.tienen@gmail.com>
4  *
5  * This file is part of paparazzi.
6  *
7  * paparazzi is free software; you can redistribute it and/or modify
8  * it under the terms of the GNU General Public License as published by
9  * the Free Software Foundation; either version 2, or (at your option)
10  * any later version.
11  *
12  * paparazzi is distributed in the hope that it will be useful,
13  * but WITHOUT ANY WARRANTY; without even the implied warranty of
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15  * GNU General Public License for more details.
16  *
17  * You should have received a copy of the GNU General Public License
18  * along with paparazzi; see the file COPYING. If not, write to
19  * the Free Software Foundation, 59 Temple Place - Suite 330,
20  * Boston, MA 02111-1307, USA.
21  */
22 
28 #ifndef IMU_H
29 #define IMU_H
30 
31 #include "math/pprz_algebra_int.h"
35 #include "generated/airframe.h"
36 
37 #ifndef IMU_MAX_SENSORS
38 #define IMU_MAX_SENSORS 4
39 #endif
40 
41 struct imu_calib_t {
42  bool neutral: 1;
43  bool scale: 1;
44  bool rotation: 1;
45  bool current: 1;
46  bool filter: 1;
47 };
48 
49 struct imu_gyro_t {
52  struct imu_calib_t calibrated;
53  struct Int32Rates scaled;
54  struct Int32Rates unscaled;
55  float temperature;
56  struct Int32Rates neutral;
57  struct Int32Rates scale[2];
58  struct Int32RMat body_to_sensor;
59  float filter_freq;
62 };
63 
64 struct imu_accel_t {
67  struct imu_calib_t calibrated;
68  struct Int32Vect3 scaled;
69  struct Int32Vect3 unscaled;
70  float temperature;
71  struct Int32Vect3 neutral;
72  struct Int32Vect3 scale[2];
73  struct Int32RMat body_to_sensor;
74  float filter_freq;
77 };
78 
79 struct imu_mag_t {
81  struct imu_calib_t calibrated;
82  struct Int32Vect3 scaled;
83  struct Int32Vect3 unscaled;
84  struct Int32Vect3 neutral;
85  struct Int32Vect3 scale[2];
86  struct FloatVect3 current_scale;
87  struct Int32RMat body_to_sensor;
88 };
89 
90 
92 struct Imu {
93  bool initialized;
101 
106 };
107 
109 extern struct Imu imu;
110 
112 extern void imu_init(void);
113 
114 extern void imu_set_defaults_gyro(uint8_t abi_id, const struct Int32RMat *imu_to_sensor, const struct Int32Rates *neutral, const struct Int32Rates *scale);
115 extern void imu_set_defaults_accel(uint8_t abi_id, const struct Int32RMat *imu_to_sensor, const struct Int32Vect3 *neutral, const struct Int32Vect3 *scale);
116 extern void imu_set_defaults_mag(uint8_t abi_id, const struct Int32RMat *imu_to_sensor, const struct Int32Vect3 *neutral, const struct Int32Vect3 *scale);
117 
118 extern struct imu_gyro_t *imu_get_gyro(uint8_t sender_id, bool create);
119 extern struct imu_accel_t *imu_get_accel(uint8_t sender_id, bool create);
120 extern struct imu_mag_t *imu_get_mag(uint8_t sender_id, bool create);
121 
122 extern void imu_SetBodyToImuPhi(float phi);
123 extern void imu_SetBodyToImuTheta(float theta);
124 extern void imu_SetBodyToImuPsi(float psi);
125 extern void imu_SetBodyToImuCurrent(float set);
126 extern void imu_ResetBodyToImu(float reset);
127 
128 #endif /* IMU_H */
static uint8_t reset[3]
Definition: baro_MS5534A.c:83
static const float scale[]
rotation matrix
angular rates
uint32_t last_stamp
Last measurement timestamp for integration.
Definition: imu.h:51
struct Int32Rates scaled
Last scaled values in body frame.
Definition: imu.h:53
struct Int32RMat body_to_sensor
Rotation from body to sensor frame (body to imu combined with imu to sensor)
Definition: imu.h:73
struct imu_calib_t calibrated
Calibration bitmask.
Definition: imu.h:81
struct imu_accel_t * imu_get_accel(uint8_t sender_id, bool create)
Find or create the accel in the imu structure.
Definition: imu.c:907
struct FloatVect3 current_scale
Current scaling multiplying.
Definition: imu.h:86
struct imu_accel_t accels[IMU_MAX_SENSORS]
The accelerometer sensors.
Definition: imu.h:95
uint8_t abi_id
ABI sensor ID.
Definition: imu.h:50
bool scale
Scale calibrated.
Definition: imu.h:43
float temperature
Temperature in degrees celcius.
Definition: imu.h:55
Butterworth2LowPass filter[3]
Lowpass filter optional.
Definition: imu.h:76
float filter_freq
Lowpass filter frequency (Hz)
Definition: imu.h:74
struct imu_gyro_t * imu_get_gyro(uint8_t sender_id, bool create)
Find or create the gyro in the imu structure.
Definition: imu.c:884
uint32_t last_stamp
Last measurement timestamp for integration.
Definition: imu.h:66
float filter_sample_freq
Lowpass filter sample frequency (Hz)
Definition: imu.h:60
struct Int32Vect3 neutral
Neutral values, compensation on unscaled->scaled.
Definition: imu.h:84
uint8_t mag_abi_send_id
Filter out and send only a specific ABI id in telemetry for the magnetometer.
Definition: imu.h:100
void imu_set_defaults_mag(uint8_t abi_id, const struct Int32RMat *imu_to_sensor, const struct Int32Vect3 *neutral, const struct Int32Vect3 *scale)
Set the defaults for a mag sensor WARNING: Should be called before sensor is publishing messages to e...
Definition: imu.c:640
struct OrientationReps body_to_imu
Rotation from body to imu (all sensors) frame.
Definition: imu.h:97
bool filter
Enable the lowpass filter.
Definition: imu.h:46
struct Int32Vect3 unscaled
Last unscaled values in sensor frame.
Definition: imu.h:69
void imu_SetBodyToImuTheta(float theta)
Definition: imu.c:990
float temperature
Temperature in degrees celcius.
Definition: imu.h:70
struct Int32Rates neutral
Neutral values, compensation on unscaled->scaled.
Definition: imu.h:56
bool current
Current calibrated.
Definition: imu.h:45
struct Int32RMat body_to_sensor
Rotation from body to sensor frame (body to imu combined with imu to sensor)
Definition: imu.h:87
bool initialized
Check if the IMU is initialized.
Definition: imu.h:93
Butterworth2LowPass filter[3]
Lowpass filter optional.
Definition: imu.h:61
void imu_set_defaults_accel(uint8_t abi_id, const struct Int32RMat *imu_to_sensor, const struct Int32Vect3 *neutral, const struct Int32Vect3 *scale)
Set the defaults for a accel sensor WARNING: Should be called before sensor is publishing messages to...
Definition: imu.c:610
struct imu_calib_t calibrated
Calibration bitmask.
Definition: imu.h:67
struct Int32Vect3 scale[2]
Scaling, first is numerator and second denominator.
Definition: imu.h:85
struct Int32Rates scale[2]
Scaling, first is numerator and second denominator.
Definition: imu.h:57
struct Imu imu
global IMU state
Definition: imu.c:422
void imu_set_defaults_gyro(uint8_t abi_id, const struct Int32RMat *imu_to_sensor, const struct Int32Rates *neutral, const struct Int32Rates *scale)
Set the defaults for a gyro sensor WARNING: Should be called before sensor is publishing messages to ...
Definition: imu.c:580
float filter_sample_freq
Lowpass filter sample frequency (Hz)
Definition: imu.h:75
struct Int32Vect3 scaled
Last scaled values in body frame.
Definition: imu.h:68
struct imu_gyro_t gyros[IMU_MAX_SENSORS]
The gyro sensors.
Definition: imu.h:94
void imu_init(void)
External functions.
Definition: imu.c:429
struct Int32RMat body_to_sensor
Rotation from body to sensor frame (body to imu combined with imu to sensor)
Definition: imu.h:58
void imu_SetBodyToImuPsi(float psi)
Definition: imu.c:998
struct Int32Rates unscaled
Last unscaled values in sensor frame.
Definition: imu.h:54
uint8_t abi_id
ABI sensor ID.
Definition: imu.h:80
void imu_SetBodyToImuCurrent(float set)
Definition: imu.c:1006
struct imu_mag_t mags[IMU_MAX_SENSORS]
The magnetometer sensors.
Definition: imu.h:96
struct Int32Vect3 scale[2]
Scaling, first is numerator and second denominator.
Definition: imu.h:72
bool neutral
Neutral values calibrated.
Definition: imu.h:42
bool b2i_set_current
flag for adjusting body_to_imu via settings.
Definition: imu.h:105
struct Int32Vect3 neutral
Neutral values, compensation on unscaled->scaled.
Definition: imu.h:71
struct Int32Vect3 unscaled
Last unscaled values in sensor frame.
Definition: imu.h:83
float filter_freq
Filter frequency.
Definition: imu.h:59
void imu_SetBodyToImuPhi(float phi)
Definition: imu.c:982
#define IMU_MAX_SENSORS
Definition: imu.h:38
void imu_ResetBodyToImu(float reset)
struct imu_calib_t calibrated
Calibration bitmask.
Definition: imu.h:52
uint8_t accel_abi_send_id
Filter out and send only a specific ABI id in telemetry for the accelerometer.
Definition: imu.h:99
struct Int32Vect3 scaled
Last scaled values in body frame.
Definition: imu.h:82
bool rotation
Rotation calibrated.
Definition: imu.h:44
struct imu_mag_t * imu_get_mag(uint8_t sender_id, bool create)
Find or create the mag in the imu structure.
Definition: imu.c:931
uint8_t gyro_abi_send_id
Filter out and send only a specific ABI id in telemetry for the gyro.
Definition: imu.h:98
uint8_t abi_id
ABI sensor ID.
Definition: imu.h:65
abstract IMU interface providing fixed point interface
Definition: imu.h:92
Definition: imu.h:49
Definition: imu.h:79
Simple first order low pass filter with bilinear transform.
Second order low pass filter structure.
Paparazzi floating point algebra.
Paparazzi fixed point algebra.
Generic orientation representation and conversions.
unsigned int uint32_t
Typedef defining 32 bit unsigned int type.
Definition: vl53l1_types.h:78
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.
Definition: vl53l1_types.h:98