Paparazzi UAS  v5.15_devel-230-gc96ce27
Paparazzi is a free software Unmanned Aircraft System.
 All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
imu_mpu6000.c
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2013-2015 Felix Ruess <felix.ruess@gmail.com>
3  * Copyright (C) 2019 Gautier Hattenberger <gautier.hattenberger@enac.fr>
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 #include "subsystems/imu.h"
29 #include "subsystems/abi.h"
30 #include "mcu_periph/spi.h"
31 
32 /* SPI defaults set in subsystem makefile, can be configured from airframe file */
33 PRINT_CONFIG_VAR(IMU_MPU_SPI_SLAVE_IDX)
34 PRINT_CONFIG_VAR(IMU_MPU_SPI_DEV)
35 
36 
37 /* MPU60x0 gyro/accel internal lowpass frequency */
38 #if !defined IMU_MPU_LOWPASS_FILTER && !defined IMU_MPU_SMPLRT_DIV
39 #if (PERIODIC_FREQUENCY >= 60) && (PERIODIC_FREQUENCY <= 120)
40 /* Accelerometer: Bandwidth 44Hz, Delay 4.9ms
41  * Gyroscope: Bandwidth 42Hz, Delay 4.8ms sampling 1kHz
42  */
43 #define IMU_MPU_LOWPASS_FILTER MPU60X0_DLPF_42HZ
44 #define IMU_MPU_SMPLRT_DIV 9
45 PRINT_CONFIG_MSG("Gyro/Accel output rate is 100Hz at 1kHz internal sampling")
46 #ifndef IMU_MPU_ACCEL_LOWPASS_FILTER
47 #define IMU_MPU_ACCEL_LOWPASS_FILTER MPU60X0_DLPF_ACC_44HZ // for ICM sensors
48 #endif
49 #elif (PERIODIC_FREQUENCY == 512) || (PERIODIC_FREQUENCY == 500)
50 /* Accelerometer: Bandwidth 260Hz, Delay 0ms
51  * Gyroscope: Bandwidth 256Hz, Delay 0.98ms sampling 8kHz
52  */
53 #define IMU_MPU_LOWPASS_FILTER MPU60X0_DLPF_256HZ
54 #define IMU_MPU_SMPLRT_DIV 3
55 PRINT_CONFIG_MSG("Gyro/Accel output rate is 2kHz at 8kHz internal sampling")
56 #ifndef IMU_MPU_ACCEL_LOWPASS_FILTER
57 #define IMU_MPU_ACCEL_LOWPASS_FILTER MPU60X0_DLPF_ACC_218HZ // for ICM sensors
58 #endif
59 #else
60 /* By default, don't go too fast */
61 #define IMU_MPU_LOWPASS_FILTER MPU60X0_DLPF_42HZ
62 #define IMU_MPU_SMPLRT_DIV 9
63 PRINT_CONFIG_MSG("Gyro/Accel output rate is 100Hz at 1kHz internal sampling")
64 #ifndef IMU_MPU_ACCEL_LOWPASS_FILTER
65 #define IMU_MPU_ACCEL_LOWPASS_FILTER MPU60X0_DLPF_ACC_44HZ // for ICM sensors
66 #endif
67 INFO("Non-default PERIODIC_FREQUENCY: using default IMU_MPU_LOWPASS_FILTER and IMU_MPU_SMPLRT_DIV.")
68 #endif
69 #endif
70 PRINT_CONFIG_VAR(IMU_MPU_LOWPASS_FILTER)
71 PRINT_CONFIG_VAR(IMU_MPU_ACCEL_LOWPASS_FILTER)
72 PRINT_CONFIG_VAR(IMU_MPU_SMPLRT_DIV)
73 
74 PRINT_CONFIG_VAR(IMU_MPU_GYRO_RANGE)
75 PRINT_CONFIG_VAR(IMU_MPU_ACCEL_RANGE)
76 
77 // Default channels order
78 #ifndef IMU_MPU_CHAN_X
79 #define IMU_MPU_CHAN_X 0
80 #endif
81 PRINT_CONFIG_VAR(IMU_MPU_CHAN_X)
82 #ifndef IMU_MPU_CHAN_Y
83 #define IMU_MPU_CHAN_Y 1
84 #endif
85 PRINT_CONFIG_VAR(IMU_MPU_CHAN_Y)
86 #ifndef IMU_MPU_CHAN_Z
87 #define IMU_MPU_CHAN_Z 2
88 #endif
89 PRINT_CONFIG_VAR(IMU_MPU_CHAN_Z)
90 
91 // Default channel signs
92 #ifndef IMU_MPU_X_SIGN
93 #define IMU_MPU_X_SIGN 1
94 #endif
95 PRINT_CONFIG_VAR(IMU_MPU_X_SIGN)
96 #ifndef IMU_MPU_Y_SIGN
97 #define IMU_MPU_Y_SIGN 1
98 #endif
99 PRINT_CONFIG_VAR(IMU_MPU_Y_SIGN)
100 #ifndef IMU_MPU_Z_SIGN
101 #define IMU_MPU_Z_SIGN 1
102 #endif
103 PRINT_CONFIG_VAR(IMU_MPU_Z_SIGN)
104 
105 
107 
109 {
110  mpu60x0_spi_init(&imu_mpu_spi.mpu, &IMU_MPU_SPI_DEV, IMU_MPU_SPI_SLAVE_IDX);
111  // change the default configuration
112  imu_mpu_spi.mpu.config.smplrt_div = IMU_MPU_SMPLRT_DIV;
114  imu_mpu_spi.mpu.config.dlpf_cfg_acc = IMU_MPU_ACCEL_LOWPASS_FILTER; // only for ICM sensors
115  imu_mpu_spi.mpu.config.gyro_range = IMU_MPU_GYRO_RANGE;
117 }
118 
119 
121 {
123 }
124 
126 {
129  uint32_t now_ts = get_sys_time_usec();
130 
131  // set channel order
132  struct Int32Vect3 accel = {
136  };
137  struct Int32Rates rates = {
141  };
142  // unscaled vector
143  VECT3_COPY(imu.accel_unscaled, accel);
144  RATES_COPY(imu.gyro_unscaled, rates);
145 
147 
148  // Scale the gyro and accelerometer
151 
152  // Send the scaled values over ABI
153  AbiSendMsgIMU_GYRO_INT32(IMU_MPU6000_ID, now_ts, &imu.gyro);
154  AbiSendMsgIMU_ACCEL_INT32(IMU_MPU6000_ID, now_ts, &imu.accel);
155  }
156 }
angular rates
void mpu60x0_spi_init(struct Mpu60x0_Spi *mpu, struct spi_periph *spi_p, uint8_t slave_idx)
Definition: mpu60x0_spi.c:31
#define IMU_MPU_CHAN_X
Definition: imu_mpu6000.c:79
#define IMU_MPU_Z_SIGN
Definition: imu_mpu6000.c:101
#define IMU_MPU_X_SIGN
Definition: imu_mpu6000.c:93
struct Mpu60x0Config config
Definition: mpu60x0_spi.h:67
void imu_mpu_spi_event(void)
Definition: imu_mpu6000.c:125
void mpu60x0_spi_event(struct Mpu60x0_Spi *mpu)
Definition: mpu60x0_spi.c:128
#define VECT3_COPY(_a, _b)
Definition: pprz_algebra.h:140
Main include for ABI (AirBorneInterface).
uint8_t smplrt_div
Sample rate divider.
Definition: mpu60x0.h:140
enum Mpu60x0ACCDLPF dlpf_cfg_acc
Digital Low Pass Filter for acceleremoter (ICM devices only)
Definition: mpu60x0.h:142
struct Imu imu
global IMU state
Definition: imu.c:108
enum Mpu60x0GyroRanges gyro_range
deg/s Range
Definition: mpu60x0.h:143
void imu_mpu_spi_periodic(void)
Definition: imu_mpu6000.c:120
enum Mpu60x0AccelRanges accel_range
g Range
Definition: mpu60x0.h:144
enum Mpu60x0DLPF dlpf_cfg
Digital Low Pass Filter.
Definition: mpu60x0.h:141
#define IMU_MPU_ACCEL_LOWPASS_FILTER
Definition: imu_mpu6000.c:65
Architecture independent SPI (Serial Peripheral Interface) API.
struct Int32Rates gyro_unscaled
unscaled gyroscope measurements
Definition: imu.h:46
struct Int32Vect3 accel
accelerometer measurements in m/s^2 in BFP with INT32_ACCEL_FRAC
Definition: imu.h:39
static void mpu60x0_spi_periodic(struct Mpu60x0_Spi *mpu)
convenience function: read or start configuration if not already initialized
Definition: mpu60x0_spi.h:78
#define IMU_MPU_CHAN_Y
Definition: imu_mpu6000.c:83
union Mpu60x0_Spi::@331 data_accel
#define IMU_MPU_SMPLRT_DIV
Definition: imu_mpu6000.c:62
#define IMU_MPU_CHAN_Z
Definition: imu_mpu6000.c:87
unsigned long uint32_t
Definition: types.h:18
PRINT_CONFIG_MSG("USE_INS_NAV_INIT defaulting to TRUE")
#define IMU_MPU_Y_SIGN
Definition: imu_mpu6000.c:97
#define IMU_MPU6000_ID
Inertial Measurement Unit interface.
void imu_scale_gyro(struct Imu *_imu)
Definition: imu_vectornav.c:43
signed long int32_t
Definition: types.h:19
volatile bool data_available
data ready flag
Definition: mpu60x0_spi.h:56
struct Int32Vect3 accel_unscaled
unscaled accelerometer measurements
Definition: imu.h:47
#define IMU_MPU_GYRO_RANGE
Definition: imu_mpu6000.h:37
void imu_scale_accel(struct Imu *_imu)
Definition: imu_vectornav.c:44
#define IMU_MPU_LOWPASS_FILTER
Definition: imu_mpu6000.c:61
#define RATES_COPY(_a, _b)
Definition: pprz_algebra.h:337
struct ImuMpu6000 imu_mpu_spi
Definition: imu_mpu6000.c:106
void imu_mpu_spi_init(void)
Definition: imu_mpu6000.c:108
uint32_t get_sys_time_usec(void)
Get the time in microseconds since startup.
Definition: sys_time_arch.c:68
#define IMU_MPU_ACCEL_RANGE
Definition: imu_mpu6000.h:41
struct Mpu60x0_Spi mpu
Definition: imu_mpu6000.h:72
struct Int32Rates gyro
gyroscope measurements in rad/s in BFP with INT32_RATE_FRAC
Definition: imu.h:38
union Mpu60x0_Spi::@332 data_rates