Paparazzi UAS  v6.3_unstable
Paparazzi is a free software Unmanned Aircraft System.
imu.c
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 #ifdef BOARD_CONFIG
29 #include BOARD_CONFIG
30 #endif
31 
32 #include "modules/imu/imu.h"
33 #include "state.h"
34 #include "modules/core/abi.h"
36 
38 #ifndef IMU_INTEGRATION
39 #define IMU_INTEGRATION false
40 #endif
41 
43 #if defined(IMU_GYRO_CALIB) && (defined(IMU_GYRO_P_SIGN) || defined(IMU_GYRO_Q_SIGN) || defined(IMU_GYRO_R_SIGN))
44 #warning "The IMU_GYRO_?_SIGN's aren't compatible with the IMU_GYRO_CALIB define in the airframe"
45 #endif
46 #ifndef IMU_GYRO_P_SIGN
47 #define IMU_GYRO_P_SIGN 1
48 #endif
49 #ifndef IMU_GYRO_Q_SIGN
50 #define IMU_GYRO_Q_SIGN 1
51 #endif
52 #ifndef IMU_GYRO_R_SIGN
53 #define IMU_GYRO_R_SIGN 1
54 #endif
55 
57 #if defined(IMU_GYRO_P_NEUTRAL) || defined(IMU_GYRO_Q_NEUTRAL) || defined(IMU_GYRO_R_NEUTRAL)
58 #define GYRO_NEUTRAL {IMU_GYRO_P_NEUTRAL, IMU_GYRO_Q_NEUTRAL, IMU_GYRO_R_NEUTRAL}
59 PRINT_CONFIG_MSG("Using single IMU gyro neutral calibration")
60 #endif
61 
62 #if defined(IMU_GYRO_P_SENS) || defined(IMU_GYRO_Q_SENS) || defined(IMU_GYRO_R_SENS)
63 #define GYRO_SCALE {{IMU_GYRO_P_SIGN*IMU_GYRO_P_SENS_NUM, IMU_GYRO_Q_SIGN*IMU_GYRO_Q_SENS_NUM, IMU_GYRO_R_SIGN*IMU_GYRO_R_SENS_NUM}, {IMU_GYRO_P_SENS_DEN, IMU_GYRO_Q_SENS_DEN, IMU_GYRO_R_SENS_DEN}}
64 PRINT_CONFIG_MSG("Using single IMU gyro sensitivity calibration")
65 #endif
66 
67 #if defined(GYRO_NEUTRAL) && defined(GYRO_SCALE)
68 #define IMU_GYRO_CALIB {{.abi_id=ABI_BROADCAST, .calibrated={.neutral=true, .scale=true}, .neutral=GYRO_NEUTRAL, .scale=GYRO_SCALE}}
69 #elif defined(GYRO_NEUTRAL)
70 #define IMU_GYRO_CALIB {{.abi_id=ABI_BROADCAST, .calibrated={.neutral=true}, .neutral=GYRO_NEUTRAL}}
71 #elif defined(GYRO_SCALE)
72 #define IMU_GYRO_CALIB {{.abi_id=ABI_BROADCAST, .calibrated={.scale=true}, .scale=GYRO_SCALE}}
73 #elif !defined(IMU_GYRO_CALIB)
74 #define IMU_GYRO_CALIB {}
75 #endif
76 
78 #if defined(IMU_ACCEL_CALIB) && (defined(IMU_ACCEL_X_SIGN) || defined(IMU_ACCEL_Y_SIGN) || defined(IMU_ACCEL_Z_SIGN))
79 #warning "The IMU_ACCEL_?_SIGN's aren't compatible with the IMU_ACCEL_CALIB define in the airframe"
80 #endif
81 #ifndef IMU_ACCEL_X_SIGN
82 #define IMU_ACCEL_X_SIGN 1
83 #endif
84 #ifndef IMU_ACCEL_Y_SIGN
85 #define IMU_ACCEL_Y_SIGN 1
86 #endif
87 #ifndef IMU_ACCEL_Z_SIGN
88 #define IMU_ACCEL_Z_SIGN 1
89 #endif
90 
92 #if defined(IMU_ACCEL_X_NEUTRAL) || defined(IMU_ACCEL_Y_NEUTRAL) || defined(IMU_ACCEL_Z_NEUTRAL)
93 #define ACCEL_NEUTRAL {IMU_ACCEL_X_NEUTRAL, IMU_ACCEL_Y_NEUTRAL, IMU_ACCEL_Z_NEUTRAL}
94 PRINT_CONFIG_MSG("Using single IMU accel neutral calibration")
95 #endif
96 
97 #if defined(IMU_ACCEL_X_SENS) || defined(IMU_ACCEL_Y_SENS) || defined(IMU_ACCEL_Z_SENS)
98 #define ACCEL_SCALE {{IMU_ACCEL_X_SIGN*IMU_ACCEL_X_SENS_NUM, IMU_ACCEL_Y_SIGN*IMU_ACCEL_Y_SENS_NUM, IMU_ACCEL_Z_SIGN*IMU_ACCEL_Z_SENS_NUM}, {IMU_ACCEL_X_SENS_DEN, IMU_ACCEL_Y_SENS_DEN, IMU_ACCEL_Z_SENS_DEN}}
99 PRINT_CONFIG_MSG("Using single IMU accel sensitivity calibration")
100 #endif
101 
102 #if defined(ACCEL_NEUTRAL) && defined(ACCEL_SCALE)
103 #define IMU_ACCEL_CALIB {{.abi_id=ABI_BROADCAST, .calibrated={.neutral=true, .scale=true}, .neutral=ACCEL_NEUTRAL, .scale=ACCEL_SCALE}}
104 #elif defined(ACCEL_NEUTRAL)
105 #define IMU_ACCEL_CALIB {{.abi_id=ABI_BROADCAST, .calibrated={.neutral=true}, .neutral=ACCEL_NEUTRAL}}
106 #elif defined(ACCEL_SCALE)
107 #define IMU_ACCEL_CALIB {{.abi_id=ABI_BROADCAST, .calibrated={.scale=true}, .scale=ACCEL_SCALE}}
108 #elif !defined(IMU_ACCEL_CALIB)
109 #define IMU_ACCEL_CALIB {}
110 #endif
111 
113 #if defined(IMU_MAG_CALIB) && (defined(IMU_MAG_X_SIGN) || defined(IMU_MAG_Y_SIGN) || defined(IMU_MAG_Z_SIGN))
114 #warning "The IMU_MAG_?_SIGN's aren't compatible with the IMU_MAG_CALIB define in the airframe"
115 #endif
116 #ifndef IMU_MAG_X_SIGN
117 #define IMU_MAG_X_SIGN 1
118 #endif
119 #ifndef IMU_MAG_Y_SIGN
120 #define IMU_MAG_Y_SIGN 1
121 #endif
122 #ifndef IMU_MAG_Z_SIGN
123 #define IMU_MAG_Z_SIGN 1
124 #endif
125 
127 #if defined(IMU_MAG_X_NEUTRAL) || defined(IMU_MAG_Y_NEUTRAL) || defined(IMU_MAG_Z_NEUTRAL)
128 #define MAG_NEUTRAL {IMU_MAG_X_NEUTRAL, IMU_MAG_Y_NEUTRAL, IMU_MAG_Z_NEUTRAL}
129 PRINT_CONFIG_MSG("Using single IMU mag neutral calibration")
130 #endif
131 
132 #if defined(IMU_MAG_X_SENS) || defined(IMU_MAG_Y_SENS) || defined(IMU_MAG_Z_SENS)
133 #define MAG_SCALE {{IMU_MAG_X_SIGN*IMU_MAG_X_SENS_NUM, IMU_MAG_Y_SIGN*IMU_MAG_Y_SENS_NUM, IMU_MAG_Z_SIGN*IMU_MAG_Z_SENS_NUM}, {IMU_MAG_X_SENS_DEN, IMU_MAG_Y_SENS_DEN, IMU_MAG_Z_SENS_DEN}}
134 PRINT_CONFIG_MSG("Using single IMU mag sensitivity calibration")
135 #endif
136 
137 #if defined(MAG_NEUTRAL) && defined(MAG_SCALE)
138 #define IMU_MAG_CALIB {{.abi_id=ABI_BROADCAST, .calibrated={.neutral=true, .scale=true}, .neutral=MAG_NEUTRAL, .scale=MAG_SCALE}}
139 #elif defined(MAG_NEUTRAL)
140 #define IMU_MAG_CALIB {{.abi_id=ABI_BROADCAST, .calibrated={.neutral=true}, .neutral=MAG_NEUTRAL}}
141 #elif defined(MAG_SCALE)
142 #define IMU_MAG_CALIB {{.abi_id=ABI_BROADCAST, .calibrated={.scale=true}, .scale=MAG_SCALE}}
143 #elif !defined(IMU_MAG_CALIB)
144 #define IMU_MAG_CALIB {}
145 #endif
146 
147 
149 #if !defined(IMU_BODY_TO_IMU_PHI) && !defined(IMU_BODY_TO_IMU_THETA) && !defined(IMU_BODY_TO_IMU_PSI)
150 #define IMU_BODY_TO_IMU_PHI 0
151 #define IMU_BODY_TO_IMU_THETA 0
152 #define IMU_BODY_TO_IMU_PSI 0
153 #endif
154 PRINT_CONFIG_VAR(IMU_BODY_TO_IMU_PHI)
155 PRINT_CONFIG_VAR(IMU_BODY_TO_IMU_THETA)
156 PRINT_CONFIG_VAR(IMU_BODY_TO_IMU_PSI)
157 
158 
159 #ifndef IMU_GYRO_ABI_SEND_ID
160 #define IMU_GYRO_ABI_SEND_ID ABI_BROADCAST
161 #endif
162 PRINT_CONFIG_VAR(IMU_GYRO_ABI_SEND_ID)
163 
164 
165 #ifndef IMU_ACCEL_ABI_SEND_ID
166 #define IMU_ACCEL_ABI_SEND_ID ABI_BROADCAST
167 #endif
168 PRINT_CONFIG_VAR(IMU_ACCEL_ABI_SEND_ID)
169 
170 
171 #ifndef IMU_MAG_ABI_SEND_ID
172 #define IMU_MAG_ABI_SEND_ID ABI_BROADCAST
173 #endif
174 PRINT_CONFIG_VAR(IMU_MAG_ABI_SEND_ID)
175 
176 
177 #if PERIODIC_TELEMETRY
179 
180 static void send_accel_raw(struct transport_tx *trans, struct link_device *dev)
181 {
183  return;
184  static uint8_t id = 0;
185  pprz_msg_send_IMU_ACCEL_RAW(trans, dev, AC_ID, &imu.accels[id].abi_id, &imu.accels[id].temperature,
186  &imu.accels[id].unscaled.x, &imu.accels[id].unscaled.y, &imu.accels[id].unscaled.z);
188  return;
189  id++;
190  if(id >= IMU_MAX_SENSORS || imu.accels[id].abi_id == ABI_DISABLE)
191  id = 0;
192 }
193 
194 static void send_accel_scaled(struct transport_tx *trans, struct link_device *dev)
195 {
197  return;
198  static uint8_t id = 0;
199  pprz_msg_send_IMU_ACCEL_SCALED(trans, dev, AC_ID, &imu.accels[id].abi_id,
200  &imu.accels[id].scaled.x, &imu.accels[id].scaled.y, &imu.accels[id].scaled.z);
202  return;
203  id++;
204  if(id >= IMU_MAX_SENSORS || imu.accels[id].abi_id == ABI_DISABLE)
205  id = 0;
206 }
207 
208 static void send_accel(struct transport_tx *trans, struct link_device *dev)
209 {
211  return;
212  static uint8_t id = 0;
213  struct FloatVect3 accel_float;
215  pprz_msg_send_IMU_ACCEL(trans, dev, AC_ID, &imu.accels[id].abi_id,
218  return;
219  id++;
220  if(id >= IMU_MAX_SENSORS || imu.accels[id].abi_id == ABI_DISABLE)
221  id = 0;
222 }
223 
224 static void send_gyro_raw(struct transport_tx *trans, struct link_device *dev)
225 {
227  return;
228  static uint8_t id = 0;
229  pprz_msg_send_IMU_GYRO_RAW(trans, dev, AC_ID, &imu.gyros[id].abi_id, &imu.gyros[id].temperature,
230  &imu.gyros[id].unscaled.p, &imu.gyros[id].unscaled.q, &imu.gyros[id].unscaled.r);
232  return;
233  id++;
234  if(id >= IMU_MAX_SENSORS || imu.gyros[id].abi_id == ABI_DISABLE)
235  id = 0;
236 }
237 
238 static void send_gyro_scaled(struct transport_tx *trans, struct link_device *dev)
239 {
241  return;
242  static uint8_t id = 0;
243  pprz_msg_send_IMU_GYRO_SCALED(trans, dev, AC_ID, &imu.gyros[id].abi_id,
244  &imu.gyros[id].scaled.p, &imu.gyros[id].scaled.q, &imu.gyros[id].scaled.r);
246  return;
247  id++;
248  if(id >= IMU_MAX_SENSORS || imu.gyros[id].abi_id == ABI_DISABLE)
249  id = 0;
250 }
251 
252 static void send_gyro(struct transport_tx *trans, struct link_device *dev)
253 {
255  return;
256  static uint8_t id = 0;
257  struct FloatRates gyro_float;
258  RATES_FLOAT_OF_BFP(gyro_float, imu.gyros[id].scaled);
259  pprz_msg_send_IMU_GYRO(trans, dev, AC_ID, &imu.gyros[id].abi_id,
260  &gyro_float.p, &gyro_float.q, &gyro_float.r);
262  return;
263  id++;
264  if(id >= IMU_MAX_SENSORS || imu.gyros[id].abi_id == ABI_DISABLE)
265  id = 0;
266 }
267 
268 static void send_mag_raw(struct transport_tx *trans, struct link_device *dev)
269 {
271  return;
272  static uint8_t id = 0;
273  pprz_msg_send_IMU_MAG_RAW(trans, dev, AC_ID, &imu.mags[id].abi_id,
274  &imu.mags[id].unscaled.x, &imu.mags[id].unscaled.y, &imu.mags[id].unscaled.z);
276  return;
277  id++;
278  if(id >= IMU_MAX_SENSORS || imu.mags[id].abi_id == ABI_DISABLE)
279  id = 0;
280 }
281 
282 static void send_mag_scaled(struct transport_tx *trans, struct link_device *dev)
283 {
285  return;
286  static uint8_t id = 0;
287  pprz_msg_send_IMU_MAG_SCALED(trans, dev, AC_ID, &imu.mags[id].abi_id ,
288  &imu.mags[id].scaled.x, &imu.mags[id].scaled.y, &imu.mags[id].scaled.z);
290  return;
291  id++;
292  if(id >= IMU_MAX_SENSORS || imu.mags[id].abi_id == ABI_DISABLE)
293  id = 0;
294 }
295 
296 static void send_mag(struct transport_tx *trans, struct link_device *dev)
297 {
299  return;
300  static uint8_t id = 0;
301  struct FloatVect3 mag_float;
303  pprz_msg_send_IMU_MAG(trans, dev, AC_ID, &imu.mags[id].abi_id,
306  return;
307  id++;
308  if(id >= IMU_MAX_SENSORS || imu.mags[id].abi_id == ABI_DISABLE)
309  id = 0;
310 }
311 
312 static void send_mag_current(struct transport_tx *trans, struct link_device *dev)
313 {
315  return;
316  static uint8_t id = 0;
317  pprz_msg_send_IMU_MAG_CURRENT_CALIBRATION(trans, dev, AC_ID,
318  &imu.mags[id].abi_id,
319  &imu.mags[id].unscaled.x,
320  &imu.mags[id].unscaled.y,
321  &imu.mags[id].unscaled.z,
324  return;
325  id++;
326  if(id >= IMU_MAX_SENSORS || imu.mags[id].abi_id == ABI_DISABLE)
327  id = 0;
328 }
329 
330 #endif /* PERIODIC_TELEMETRY */
331 
332 struct Imu imu = {0};
334 static void imu_gyro_raw_cb(uint8_t sender_id, uint32_t stamp, struct Int32Rates *data, uint8_t samples, float rate, float temp);
335 static void imu_accel_raw_cb(uint8_t sender_id, uint32_t stamp, struct Int32Vect3 *data, uint8_t samples, float rate, float temp);
336 static void imu_mag_raw_cb(uint8_t sender_id, uint32_t stamp, struct Int32Vect3 *data);
337 static void imu_set_body_to_imu_eulers(struct FloatEulers *body_to_imu_eulers);
338 
339 void imu_init(void)
340 {
341  // Set the Body to IMU rotation
343  orientationSetEulers_f(&imu.body_to_imu, &body_to_imu_eulers);
344  struct Int32RMat *body_to_imu_rmat = orientationGetRMat_i(&imu.body_to_imu);
345 
346 
347  // Set the calibrated sensors
348  struct Int32RMat body_to_sensor;
349  const struct imu_gyro_t gyro_calib[] = IMU_GYRO_CALIB;
350  const struct imu_accel_t accel_calib[] = IMU_ACCEL_CALIB;
351  const struct imu_mag_t mag_calib[] = IMU_MAG_CALIB;
352  const uint8_t gyro_calib_len = sizeof(gyro_calib) / sizeof(struct imu_gyro_t);
353  const uint8_t accel_calib_len = sizeof(accel_calib) / sizeof(struct imu_accel_t);
354  const uint8_t mag_calib_len = sizeof(mag_calib) / sizeof(struct imu_mag_t);
355 
356  // Initialize the sensors to default values
357  for(uint8_t i = 0; i < IMU_MAX_SENSORS; i++) {
358  /* Copy gyro calibration if needed */
359  if(i >= gyro_calib_len) {
361  imu.gyros[i].calibrated.neutral = false;
362  imu.gyros[i].calibrated.scale = false;
363  imu.gyros[i].calibrated.rotation = false;
364  } else {
365  imu.gyros[i] = gyro_calib[i];
366  }
367 
368  // Set the default safe values if not calibrated
369  if(!imu.gyros[i].calibrated.neutral) {
371  }
372  if(!imu.gyros[i].calibrated.scale) {
374  RATES_ASSIGN(imu.gyros[i].scale[1], 1, 1, 1);
375  }
376  if(!imu.gyros[i].calibrated.rotation) {
378  }
379  imu.gyros[i].last_stamp = 0;
380  int32_rmat_comp(&body_to_sensor, body_to_imu_rmat, &imu.gyros[i].body_to_sensor);
382 
383 
384  /* Copy accel calibration if needed */
385  if(i >= accel_calib_len) {
387  imu.accels[i].calibrated.neutral = false;
388  imu.accels[i].calibrated.scale = false;
389  imu.accels[i].calibrated.rotation = false;
390  } else {
391  imu.accels[i] = accel_calib[i];
392  }
393 
394  // Set the default safe values if not calibrated
395  if(!imu.accels[i].calibrated.neutral) {
397  }
398  if(!imu.accels[i].calibrated.scale) {
400  VECT3_ASSIGN(imu.accels[i].scale[1], 1, 1, 1);
401  }
402  if(!imu.accels[i].calibrated.rotation) {
404  }
405  imu.accels[i].last_stamp = 0;
406  int32_rmat_comp(&body_to_sensor, body_to_imu_rmat, &imu.accels[i].body_to_sensor);
408 
409 
410  /* Copy mag calibrated if needed */
411  if(i >= mag_calib_len) {
412  imu.mags[i].abi_id = ABI_DISABLE;
413  imu.mags[i].calibrated.neutral = false;
414  imu.mags[i].calibrated.scale = false;
415  imu.mags[i].calibrated.rotation = false;
416  imu.mags[i].calibrated.current = false;
417  } else {
418  imu.mags[i] = mag_calib[i];
419  }
420 
421  // Set the default safe values if not calibrated
422  if(!imu.mags[i].calibrated.neutral) {
424  }
425  if(!imu.mags[i].calibrated.scale) {
427  VECT3_ASSIGN(imu.mags[i].scale[1], 1, 1, 1);
428  }
429  if(!imu.mags[i].calibrated.rotation) {
431  }
432  if(!imu.mags[i].calibrated.current) {
434  }
435  int32_rmat_comp(&body_to_sensor, body_to_imu_rmat, &imu.mags[i].body_to_sensor);
437  }
438 
439  // Bind to raw measurements
440  AbiBindMsgIMU_GYRO_RAW(ABI_BROADCAST, &imu_gyro_raw_ev, imu_gyro_raw_cb);
441  AbiBindMsgIMU_ACCEL_RAW(ABI_BROADCAST, &imu_accel_raw_ev, imu_accel_raw_cb);
442  AbiBindMsgIMU_MAG_RAW(ABI_BROADCAST, &imu_mag_raw_ev, imu_mag_raw_cb);
443 
444 #if PERIODIC_TELEMETRY
445  register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_IMU_ACCEL_RAW, send_accel_raw);
446  register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_IMU_ACCEL_SCALED, send_accel_scaled);
447  register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_IMU_ACCEL, send_accel);
448  register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_IMU_GYRO_RAW, send_gyro_raw);
449  register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_IMU_GYRO_SCALED, send_gyro_scaled);
450  register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_IMU_GYRO, send_gyro);
451  register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_IMU_MAG_RAW, send_mag_raw);
452  register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_IMU_MAG_SCALED, send_mag_scaled);
454  register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_IMU_MAG_CURRENT_CALIBRATION, send_mag_current);
455 #endif // DOWNLINK
456 
457  // Set defaults
461  imu.initialized = true;
462 }
463 
472 void imu_set_defaults_gyro(uint8_t abi_id, const struct Int32RMat *imu_to_sensor, const struct Int32Rates *neutral, const struct Int32Rates *scale)
473 {
474  // Find the correct gyro
475  struct imu_gyro_t *gyro = imu_get_gyro(abi_id, true);
476  if(gyro == NULL)
477  return;
478 
479  // Copy the defaults
480  if(imu_to_sensor != NULL && !gyro->calibrated.rotation) {
481  struct Int32RMat body_to_sensor;
482  struct Int32RMat *body_to_imu = orientationGetRMat_i(&imu.body_to_imu);
483  int32_rmat_comp(&body_to_sensor, body_to_imu, imu_to_sensor);
484  RMAT_COPY(gyro->body_to_sensor, body_to_sensor);
485  }
486  if(neutral != NULL && !gyro->calibrated.neutral)
487  RATES_COPY(gyro->neutral, *neutral);
488  if(scale != NULL && !gyro->calibrated.scale) {
490  RATES_COPY(gyro->scale[1], scale[1]);
491  }
492 }
493 
502 void imu_set_defaults_accel(uint8_t abi_id, const struct Int32RMat *imu_to_sensor, const struct Int32Vect3 *neutral, const struct Int32Vect3 *scale)
503 {
504  // Find the correct accel
505  struct imu_accel_t *accel = imu_get_accel(abi_id, true);
506  if(accel == NULL)
507  return;
508 
509  // Copy the defaults
510  if(imu_to_sensor != NULL && !accel->calibrated.rotation) {
511  struct Int32RMat body_to_sensor;
512  struct Int32RMat *body_to_imu = orientationGetRMat_i(&imu.body_to_imu);
513  int32_rmat_comp(&body_to_sensor, body_to_imu, imu_to_sensor);
514  RMAT_COPY(accel->body_to_sensor, body_to_sensor);
515  }
516  if(neutral != NULL && !accel->calibrated.neutral)
517  VECT3_COPY(accel->neutral, *neutral);
518  if(scale != NULL && !accel->calibrated.scale) {
520  VECT3_COPY(accel->scale[1], scale[1]);
521  }
522 }
523 
532 void imu_set_defaults_mag(uint8_t abi_id, const struct Int32RMat *imu_to_sensor, const struct Int32Vect3 *neutral, const struct Int32Vect3 *scale)
533 {
534  // Find the correct mag
535  struct imu_mag_t *mag = imu_get_mag(abi_id, true);
536  if(mag == NULL)
537  return;
538 
539  // Copy the defaults
540  if(imu_to_sensor != NULL && !mag->calibrated.rotation) {
541  struct Int32RMat body_to_sensor;
542  struct Int32RMat *body_to_imu = orientationGetRMat_i(&imu.body_to_imu);
543  int32_rmat_comp(&body_to_sensor, body_to_imu, imu_to_sensor);
544  RMAT_COPY(mag->body_to_sensor, body_to_sensor);
545  }
546  if(neutral != NULL && !mag->calibrated.neutral)
547  VECT3_COPY(mag->neutral, *neutral);
548  if(scale != NULL && !mag->calibrated.scale) {
550  VECT3_COPY(mag->scale[1], scale[1]);
551  }
552 }
553 
554 static void imu_gyro_raw_cb(uint8_t sender_id, uint32_t stamp, struct Int32Rates *data, uint8_t samples, float rate, float temp)
555 {
556  // Find the correct gyro
557  struct imu_gyro_t *gyro = imu_get_gyro(sender_id, true);
558  if(gyro == NULL || samples < 1)
559  return;
560 
561  // Copy last sample as unscaled
562  RATES_COPY(gyro->unscaled, data[samples-1]);
563 
564  // Scale the gyro
565  struct Int32Rates scaled, scaled_rot;
566  scaled.p = (gyro->unscaled.p - gyro->neutral.p) * gyro->scale[0].p / gyro->scale[1].p;
567  scaled.q = (gyro->unscaled.q - gyro->neutral.q) * gyro->scale[0].q / gyro->scale[1].q;
568  scaled.r = (gyro->unscaled.r - gyro->neutral.r) * gyro->scale[0].r / gyro->scale[1].r;
569 
570  // Rotate the sensor
571  int32_rmat_transp_ratemult(&scaled_rot, &gyro->body_to_sensor, &scaled);
572 
573 #if IMU_INTEGRATION
574  // Only integrate if we have gotten a previous measurement and didn't overflow the timer
575  if(!isnan(rate) && gyro->last_stamp > 0 && stamp > gyro->last_stamp) {
576  struct FloatRates integrated;
577 
578  // Trapezoidal integration (TODO: coning correction)
579  integrated.p = RATE_FLOAT_OF_BFP(gyro->scaled.p + scaled_rot.p) * 0.5f;
580  integrated.q = RATE_FLOAT_OF_BFP(gyro->scaled.q + scaled_rot.q) * 0.5f;
581  integrated.r = RATE_FLOAT_OF_BFP(gyro->scaled.r + scaled_rot.r) * 0.5f;
582 
583  // Only perform multiple integrations in sensor frame if needed
584  if(samples > 1) {
585  struct FloatRates integrated_sensor;
586  struct FloatRMat body_to_sensor;
587  // Rotate back to sensor frame
588  RMAT_FLOAT_OF_BFP(body_to_sensor, gyro->body_to_sensor);
589  float_rmat_ratemult(&integrated_sensor, &body_to_sensor, &integrated);
590 
591  // Add all the other samples
592  for(uint8_t i = 0; i < samples-1; i++) {
593  integrated_sensor.p += RATE_FLOAT_OF_BFP((data[i].p - gyro->neutral.p) * gyro->scale[0].p / gyro->scale[1].p);
594  integrated_sensor.q += RATE_FLOAT_OF_BFP((data[i].q - gyro->neutral.q) * gyro->scale[0].q / gyro->scale[1].q);
595  integrated_sensor.r += RATE_FLOAT_OF_BFP((data[i].r - gyro->neutral.r) * gyro->scale[0].r / gyro->scale[1].r);
596  }
597 
598  // Rotate to body frame
599  float_rmat_transp_ratemult(&integrated, &body_to_sensor, &integrated_sensor);
600  }
601 
602  // Divide by the time of the collected samples
603  integrated.p = integrated.p * (1.f / rate);
604  integrated.q = integrated.q * (1.f / rate);
605  integrated.r = integrated.r * (1.f / rate);
606 
607  // Send the integrated values
608  uint16_t dt = (1e6 / rate) * samples;
609  AbiSendMsgIMU_GYRO_INT(sender_id, stamp, &integrated, dt);
610  }
611 #else
612  (void)rate; // Surpress compile warning not used
613 #endif
614 
615  // Copy and send
616  gyro->temperature = temp;
617  RATES_COPY(gyro->scaled, scaled_rot);
618  AbiSendMsgIMU_GYRO(sender_id, stamp, &gyro->scaled);
619  gyro->last_stamp = stamp;
620 }
621 
622 static void imu_accel_raw_cb(uint8_t sender_id, uint32_t stamp, struct Int32Vect3 *data, uint8_t samples, float rate, float temp)
623 {
624  // Find the correct accel
625  struct imu_accel_t *accel = imu_get_accel(sender_id, true);
626  if(accel == NULL || samples < 1)
627  return;
628 
629  // Copy last sample as unscaled
630  VECT3_COPY(accel->unscaled, data[samples-1]);
631 
632  // Scale the accel
633  struct Int32Vect3 scaled, scaled_rot;
634  scaled.x = (accel->unscaled.x - accel->neutral.x) * accel->scale[0].x / accel->scale[1].x;
635  scaled.y = (accel->unscaled.y - accel->neutral.y) * accel->scale[0].y / accel->scale[1].y;
636  scaled.z = (accel->unscaled.z - accel->neutral.z) * accel->scale[0].z / accel->scale[1].z;
637 
638  // Rotate the sensor
639  int32_rmat_transp_vmult(&scaled_rot, &accel->body_to_sensor, &scaled);
640 
641 #if IMU_INTEGRATION
642  // Only integrate if we have gotten a previous measurement and didn't overflow the timer
643  if(!isnan(rate) && accel->last_stamp > 0 && stamp > accel->last_stamp) {
644  struct FloatVect3 integrated;
645 
646  // Trapezoidal integration
647  integrated.x = ACCEL_FLOAT_OF_BFP(accel->scaled.x + scaled_rot.x) * 0.5f;
648  integrated.y = ACCEL_FLOAT_OF_BFP(accel->scaled.y + scaled_rot.y) * 0.5f;
649  integrated.z = ACCEL_FLOAT_OF_BFP(accel->scaled.z + scaled_rot.z) * 0.5f;
650 
651  // Only perform multiple integrations in sensor frame if needed
652  if(samples > 1) {
653  struct FloatVect3 integrated_sensor;
654  struct FloatRMat body_to_sensor;
655  // Rotate back to sensor frame
656  RMAT_FLOAT_OF_BFP(body_to_sensor, accel->body_to_sensor);
657  float_rmat_vmult(&integrated_sensor, &body_to_sensor, &integrated);
658 
659  // Add all the other samples
660  for(uint8_t i = 0; i < samples-1; i++) {
661  integrated_sensor.x += ACCEL_FLOAT_OF_BFP((data[i].x - accel->neutral.x) * accel->scale[0].x / accel->scale[1].x);
662  integrated_sensor.y += ACCEL_FLOAT_OF_BFP((data[i].y - accel->neutral.y) * accel->scale[0].y / accel->scale[1].y);
663  integrated_sensor.z += ACCEL_FLOAT_OF_BFP((data[i].z - accel->neutral.z) * accel->scale[0].z / accel->scale[1].z);
664  }
665 
666  // Rotate to body frame
667  float_rmat_transp_vmult(&integrated, &body_to_sensor, &integrated_sensor);
668  }
669 
670  // Divide by the time of the collected samples
671  integrated.x = integrated.x * (1.f / rate);
672  integrated.y = integrated.y * (1.f / rate);
673  integrated.z = integrated.z * (1.f / rate);
674 
675  // Send the integrated values
676  uint16_t dt = (1e6 / rate) * samples;
677  AbiSendMsgIMU_ACCEL_INT(sender_id, stamp, &integrated, dt);
678  }
679 #else
680  (void)rate; // Surpress compile warning not used
681 #endif
682 
683  // Copy and send
684  accel->temperature = temp;
685  VECT3_COPY(accel->scaled, scaled_rot);
686  AbiSendMsgIMU_ACCEL(sender_id, stamp, &accel->scaled);
687  accel->last_stamp = stamp;
688 }
689 
690 static void imu_mag_raw_cb(uint8_t sender_id, uint32_t stamp, struct Int32Vect3 *data)
691 {
692  // Find the correct mag
693  struct imu_mag_t *mag = imu_get_mag(sender_id, true);
694  if(mag == NULL)
695  return;
696 
697  // Calculate current compensation
698  struct Int32Vect3 mag_correction;
699  mag_correction.x = (int32_t)(mag->current_scale.x * (float) electrical.current);
700  mag_correction.y = (int32_t)(mag->current_scale.y * (float) electrical.current);
701  mag_correction.z = (int32_t)(mag->current_scale.z * (float) electrical.current);
702 
703  // Copy last sample as unscaled
704  VECT3_COPY(mag->unscaled, *data);
705 
706  // Scale the mag
707  struct Int32Vect3 scaled;
708  scaled.x = (mag->unscaled.x - mag_correction.x - mag->neutral.x) * mag->scale[0].x / mag->scale[1].x;
709  scaled.y = (mag->unscaled.y - mag_correction.y - mag->neutral.y) * mag->scale[0].y / mag->scale[1].y;
710  scaled.z = (mag->unscaled.z - mag_correction.z - mag->neutral.z) * mag->scale[0].z / mag->scale[1].z;
711 
712  // Rotate the sensor
713  int32_rmat_transp_vmult(&mag->scaled, &mag->body_to_sensor, &scaled);
714  AbiSendMsgIMU_MAG(sender_id, stamp, &mag->scaled);
715 }
716 
724 struct imu_gyro_t *imu_get_gyro(uint8_t sender_id, bool create) {
725  // Find the correct gyro or create index
726  // If abi_id was set to broadcast (assuming a single IMU case), the first request takes the index for himself
727  struct imu_gyro_t *gyro = NULL;
728  for(uint8_t i = 0; i < IMU_MAX_SENSORS; i++) {
729  if(imu.gyros[i].abi_id == sender_id || (create && (imu.gyros[i].abi_id == ABI_BROADCAST || imu.gyros[i].abi_id == ABI_DISABLE))) {
730  gyro = &imu.gyros[i];
731  gyro->abi_id = sender_id;
732  break;
733  } else if(sender_id == ABI_BROADCAST && imu.gyros[i].abi_id != ABI_DISABLE) {
734  gyro = &imu.gyros[i];
735  }
736  }
737  return gyro;
738 }
739 
747 struct imu_accel_t *imu_get_accel(uint8_t sender_id, bool create) {
748  // Find the correct accel
749  // If abi_id was set to broadcast (assuming a single IMU case), the first request takes the index for himself
750  struct imu_accel_t *accel = NULL;
751  for(uint8_t i = 0; i < IMU_MAX_SENSORS; i++) {
752  if(imu.accels[i].abi_id == sender_id || (create && (imu.accels[i].abi_id == ABI_BROADCAST || imu.accels[i].abi_id == ABI_DISABLE))) {
753  accel = &imu.accels[i];
754  accel->abi_id = sender_id;
755  break;
756  } else if(sender_id == ABI_BROADCAST && imu.accels[i].abi_id != ABI_DISABLE) {
757  accel = &imu.accels[i];
758  }
759  }
760 
761  return accel;
762 }
763 
771 struct imu_mag_t *imu_get_mag(uint8_t sender_id, bool create) {
772  // Find the correct mag
773  // If abi_id was set to broadcast (assuming a single IMU case), the first request takes the index for himself
774  struct imu_mag_t *mag = NULL;
775  for(uint8_t i = 0; i < IMU_MAX_SENSORS; i++) {
776  if(imu.mags[i].abi_id == sender_id || (create && (imu.mags[i].abi_id == ABI_BROADCAST || imu.mags[i].abi_id == ABI_DISABLE))) {
777  mag = &imu.mags[i];
778  mag->abi_id = sender_id;
779  break;
780  } else if(sender_id == ABI_BROADCAST && imu.mags[i].abi_id != ABI_DISABLE) {
781  mag = &imu.mags[i];
782  }
783  }
784 
785  return mag;
786 }
787 
793 static void imu_set_body_to_imu_eulers(struct FloatEulers *body_to_imu_eulers)
794 {
795  struct Int32RMat new_body_to_imu, diff_body_to_imu;
796  struct Int32Eulers body_to_imu_eulers_i;
797  // Convert to RMat
798  struct Int32RMat *old_body_to_imu = orientationGetRMat_i(&imu.body_to_imu);
799  EULERS_BFP_OF_REAL(body_to_imu_eulers_i, *body_to_imu_eulers);
800  int32_rmat_of_eulers(&new_body_to_imu, &body_to_imu_eulers_i);
801 
802  // Calculate the difference between old and new
803  int32_rmat_comp_inv(&diff_body_to_imu, &new_body_to_imu, old_body_to_imu);
804 
805  // Apply the difference to all sensors
806  struct Int32RMat old_rmat;
807  for(uint8_t i = 0; i < IMU_MAX_SENSORS; i++) {
808  old_rmat = imu.gyros[i].body_to_sensor;
809  int32_rmat_comp(&imu.gyros[i].body_to_sensor, &diff_body_to_imu, &old_rmat);
810 
811  old_rmat = imu.accels[i].body_to_sensor;
812  int32_rmat_comp(&imu.accels[i].body_to_sensor, &diff_body_to_imu, &old_rmat);
813 
814  old_rmat = imu.mags[i].body_to_sensor;
815  int32_rmat_comp(&imu.mags[i].body_to_sensor, &diff_body_to_imu, &old_rmat);
816  }
817 
818  // Set the current body to imu
819  orientationSetEulers_f(&imu.body_to_imu, body_to_imu_eulers);
820 }
821 
822 void imu_SetBodyToImuPhi(float phi)
823 {
824  struct FloatEulers body_to_imu_eulers;
825  body_to_imu_eulers = *orientationGetEulers_f(&imu.body_to_imu);
826  body_to_imu_eulers.phi = phi;
827  imu_set_body_to_imu_eulers(&body_to_imu_eulers);
828 }
829 
831 {
832  struct FloatEulers body_to_imu_eulers;
833  body_to_imu_eulers = *orientationGetEulers_f(&imu.body_to_imu);
834  body_to_imu_eulers.theta = theta;
835  imu_set_body_to_imu_eulers(&body_to_imu_eulers);
836 }
837 
839 {
840  struct FloatEulers body_to_imu_eulers;
841  body_to_imu_eulers = *orientationGetEulers_f(&imu.body_to_imu);
842  body_to_imu_eulers.psi = psi;
843  imu_set_body_to_imu_eulers(&body_to_imu_eulers);
844 }
845 
846 void imu_SetBodyToImuCurrent(float set)
847 {
848  imu.b2i_set_current = set;
849 
850  if (imu.b2i_set_current) {
851  // adjust imu_to_body roll and pitch by current NedToBody roll and pitch
852  struct FloatEulers body_to_imu_eulers;
853  body_to_imu_eulers = *orientationGetEulers_f(&imu.body_to_imu);
854  if (stateIsAttitudeValid()) {
855  // adjust imu_to_body roll and pitch by current NedToBody roll and pitch
856  body_to_imu_eulers.phi += stateGetNedToBodyEulers_f()->phi;
857  body_to_imu_eulers.theta += stateGetNedToBodyEulers_f()->theta;
858  imu_set_body_to_imu_eulers(&body_to_imu_eulers);
859  } else {
860  // indicate that we couldn't set to current roll/pitch
861  imu.b2i_set_current = false;
862  }
863  } else {
864  // reset to BODY_TO_IMU as defined in airframe file
866  imu_set_body_to_imu_eulers(&body_to_imu_eulers);
867  }
868 }
Main include for ABI (AirBorneInterface).
#define ABI_DISABLE
Reserved ABI ID to disable callback.
Definition: abi_common.h:64
#define ABI_BROADCAST
Broadcast address.
Definition: abi_common.h:58
Event structure to store callbacks in a linked list.
Definition: abi_common.h:67
struct FloatVect3 accel_float
struct FloatVect3 mag_float
static const float scale[]
struct Electrical electrical
Definition: electrical.c:66
Interface for electrical status: supply voltage, current, battery status, etc.
float current
current in A
Definition: electrical.h:46
float q
in rad/s
float phi
in radians
float p
in rad/s
float r
in rad/s
float theta
in radians
float psi
in radians
void float_rmat_ratemult(struct FloatRates *rb, struct FloatRMat *m_a2b, struct FloatRates *ra)
rotate anglular rates by rotation matrix.
void float_rmat_transp_ratemult(struct FloatRates *rb, struct FloatRMat *m_b2a, struct FloatRates *ra)
rotate anglular rates by transposed rotation matrix.
void float_rmat_transp_vmult(struct FloatVect3 *vb, struct FloatRMat *m_b2a, struct FloatVect3 *va)
rotate 3D vector by transposed rotation matrix.
void float_rmat_vmult(struct FloatVect3 *vb, struct FloatRMat *m_a2b, struct FloatVect3 *va)
rotate 3D vector by rotation matrix.
euler angles
rotation matrix
angular rates
#define MAGS_FLOAT_OF_BFP(_ef, _ei)
Definition: pprz_algebra.h:807
#define RATES_COPY(_a, _b)
Definition: pprz_algebra.h:337
#define RATES_ASSIGN(_ra, _p, _q, _r)
Definition: pprz_algebra.h:330
#define EULERS_BFP_OF_REAL(_ei, _ef)
Definition: pprz_algebra.h:715
#define RMAT_FLOAT_OF_BFP(_ef, _ei)
Definition: pprz_algebra.h:733
#define RMAT_COPY(_o, _i)
Definition: pprz_algebra.h:704
#define VECT3_ASSIGN(_a, _x, _y, _z)
Definition: pprz_algebra.h:125
#define VECT3_COPY(_a, _b)
Definition: pprz_algebra.h:140
#define RATES_FLOAT_OF_BFP(_rf, _ri)
Definition: pprz_algebra.h:759
#define ACCELS_FLOAT_OF_BFP(_ef, _ei)
Definition: pprz_algebra.h:795
int32_t p
in rad/s with INT32_RATE_FRAC
int32_t r
in rad/s with INT32_RATE_FRAC
int32_t q
in rad/s with INT32_RATE_FRAC
#define INT_RATES_ZERO(_e)
#define int32_rmat_of_eulers
Rotation matrix from Euler angles.
#define RATE_FLOAT_OF_BFP(_ai)
void int32_rmat_comp_inv(struct Int32RMat *m_a2b, const struct Int32RMat *m_a2c, const struct Int32RMat *m_b2c)
Composition (multiplication) of two rotation matrices.
void int32_rmat_transp_ratemult(struct Int32Rates *rb, struct Int32RMat *m_b2a, struct Int32Rates *ra)
rotate anglular rates by transposed rotation matrix.
#define INT_VECT3_ZERO(_v)
void int32_rmat_transp_vmult(struct Int32Vect3 *vb, struct Int32RMat *m_b2a, struct Int32Vect3 *va)
rotate 3D vector by transposed rotation matrix.
void int32_rmat_comp(struct Int32RMat *m_a2c, const struct Int32RMat *m_a2b, const struct Int32RMat *m_b2c)
Composition (multiplication) of two rotation matrices.
static void int32_rmat_identity(struct Int32RMat *rm)
initialises a rotation matrix to identity
#define ACCEL_FLOAT_OF_BFP(_ai)
euler angles
rotation matrix
angular rates
static struct Int32RMat * orientationGetRMat_i(struct OrientationReps *orientation)
Get vehicle body attitude rotation matrix (int).
static void orientationSetEulers_f(struct OrientationReps *orientation, struct FloatEulers *eulers)
Set vehicle body attitude from euler angles (float).
static struct FloatEulers * orientationGetEulers_f(struct OrientationReps *orientation)
Get vehicle body attitude euler angles (float).
static bool stateIsAttitudeValid(void)
Test if attitudes are valid.
Definition: state.h:1067
static struct FloatEulers * stateGetNedToBodyEulers_f(void)
Get vehicle body attitude euler angles (float).
Definition: state.h:1143
#define IMU_MAG_ABI_SEND_ID
Which mag measurements to send over telemetry/logging.
Definition: imu.c:172
#define IMU_GYRO_ABI_SEND_ID
Which gyro measurements to send over telemetry/logging.
Definition: imu.c:160
#define IMU_MAG_CALIB
Default mag calibration is for single IMU with old format.
Definition: imu.c:144
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:747
static void imu_gyro_raw_cb(uint8_t sender_id, uint32_t stamp, struct Int32Rates *data, uint8_t samples, float rate, float temp)
Definition: imu.c:554
#define IMU_MAG_Y_SIGN
Definition: imu.c:120
#define IMU_BODY_TO_IMU_THETA
Definition: imu.c:151
static void send_mag_raw(struct transport_tx *trans, struct link_device *dev)
Definition: imu.c:268
#define IMU_GYRO_P_SIGN
By default gyro signs are positive for single IMU with old format or defaults.
Definition: imu.c:47
#define IMU_ACCEL_Y_SIGN
Definition: imu.c:85
static abi_event imu_accel_raw_ev
Definition: imu.c:333
static abi_event imu_mag_raw_ev
Definition: imu.c:333
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:724
#define IMU_MAG_X_SIGN
By default mag signs are positive for single IMU with old format and defaults.
Definition: imu.c:117
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:532
void imu_SetBodyToImuTheta(float theta)
Definition: imu.c:830
#define IMU_ACCEL_X_SIGN
By default accel signs are positive for single IMU with old format and defaults.
Definition: imu.c:82
#define IMU_BODY_TO_IMU_PHI
Default body to imu is 0 (radians)
Definition: imu.c:150
static void imu_accel_raw_cb(uint8_t sender_id, uint32_t stamp, struct Int32Vect3 *data, uint8_t samples, float rate, float temp)
Definition: imu.c:622
#define IMU_ACCEL_CALIB
Default accel calibration is for single IMU with old format.
Definition: imu.c:109
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:502
static void imu_set_body_to_imu_eulers(struct FloatEulers *body_to_imu_eulers)
Set the body to IMU rotation in eulers This will update all the sensor values.
Definition: imu.c:793
static void send_mag_scaled(struct transport_tx *trans, struct link_device *dev)
Definition: imu.c:282
static void send_mag_current(struct transport_tx *trans, struct link_device *dev)
Definition: imu.c:312
struct Imu imu
global IMU state
Definition: imu.c:332
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:472
#define IMU_BODY_TO_IMU_PSI
Definition: imu.c:152
#define IMU_GYRO_CALIB
Default gyro calibration is for single IMU with old format.
Definition: imu.c:74
#define IMU_MAG_Z_SIGN
Definition: imu.c:123
void imu_init(void)
External functions.
Definition: imu.c:339
void imu_SetBodyToImuPsi(float psi)
Definition: imu.c:838
static abi_event imu_gyro_raw_ev
Definition: imu.c:333
static void send_accel_raw(struct transport_tx *trans, struct link_device *dev)
Definition: imu.c:180
#define IMU_GYRO_R_SIGN
Definition: imu.c:53
void imu_SetBodyToImuCurrent(float set)
Definition: imu.c:846
static void send_gyro_scaled(struct transport_tx *trans, struct link_device *dev)
Definition: imu.c:238
static void send_gyro(struct transport_tx *trans, struct link_device *dev)
Definition: imu.c:252
void imu_SetBodyToImuPhi(float phi)
Definition: imu.c:822
static void send_accel(struct transport_tx *trans, struct link_device *dev)
Definition: imu.c:208
static void imu_mag_raw_cb(uint8_t sender_id, uint32_t stamp, struct Int32Vect3 *data)
Definition: imu.c:690
#define IMU_ACCEL_Z_SIGN
Definition: imu.c:88
static void send_accel_scaled(struct transport_tx *trans, struct link_device *dev)
Definition: imu.c:194
static void send_mag(struct transport_tx *trans, struct link_device *dev)
Definition: imu.c:296
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:771
static void send_gyro_raw(struct transport_tx *trans, struct link_device *dev)
Definition: imu.c:224
#define IMU_ACCEL_ABI_SEND_ID
Which accel measurements to send over telemetry/logging.
Definition: imu.c:166
#define IMU_GYRO_Q_SIGN
Definition: imu.c:50
Inertial Measurement Unit interface.
uint32_t last_stamp
Last measurement timestamp for integration.
Definition: imu.h:49
struct Int32Rates scaled
Last scaled values in body frame.
Definition: imu.h:51
struct Int32RMat body_to_sensor
Rotation from body to sensor frame (body to imu combined with imu to sensor)
Definition: imu.h:68
struct imu_calib_t calibrated
Calibration bitmask.
Definition: imu.h:73
struct FloatVect3 current_scale
Current scaling multiplying.
Definition: imu.h:78
struct imu_accel_t accels[IMU_MAX_SENSORS]
The accelerometer sensors.
Definition: imu.h:87
uint8_t abi_id
ABI sensor ID.
Definition: imu.h:48
bool scale
Scale calibrated.
Definition: imu.h:42
float temperature
Temperature in degrees celcius.
Definition: imu.h:53
uint32_t last_stamp
Last measurement timestamp for integration.
Definition: imu.h:61
struct Int32Vect3 neutral
Neutral values, compensation on unscaled->scaled.
Definition: imu.h:76
uint8_t mag_abi_send_id
Filter out and send only a specific ABI id in telemetry for the magnetometer.
Definition: imu.h:92
struct OrientationReps body_to_imu
Rotation from body to imu (all sensors) frame.
Definition: imu.h:89
struct Int32Vect3 unscaled
Last unscaled values in sensor frame.
Definition: imu.h:64
float temperature
Temperature in degrees celcius.
Definition: imu.h:65
struct Int32Rates neutral
Neutral values, compensation on unscaled->scaled.
Definition: imu.h:54
bool current
Current calibrated.
Definition: imu.h:44
struct Int32RMat body_to_sensor
Rotation from body to sensor frame (body to imu combined with imu to sensor)
Definition: imu.h:79
bool initialized
Check if the IMU is initialized.
Definition: imu.h:85
struct imu_calib_t calibrated
Calibration bitmask.
Definition: imu.h:62
struct Int32Vect3 scale[2]
Scaling, first is numerator and second denominator.
Definition: imu.h:77
struct Int32Rates scale[2]
Scaling, first is numerator and second denominator.
Definition: imu.h:55
struct Int32Vect3 scaled
Last scaled values in body frame.
Definition: imu.h:63
struct imu_gyro_t gyros[IMU_MAX_SENSORS]
The gyro sensors.
Definition: imu.h:86
struct Int32RMat body_to_sensor
Rotation from body to sensor frame (body to imu combined with imu to sensor)
Definition: imu.h:56
struct Int32Rates unscaled
Last unscaled values in sensor frame.
Definition: imu.h:52
uint8_t abi_id
ABI sensor ID.
Definition: imu.h:72
struct imu_mag_t mags[IMU_MAX_SENSORS]
The magnetometer sensors.
Definition: imu.h:88
struct Int32Vect3 scale[2]
Scaling, first is numerator and second denominator.
Definition: imu.h:67
bool neutral
Neutral values calibrated.
Definition: imu.h:41
bool b2i_set_current
flag for adjusting body_to_imu via settings.
Definition: imu.h:97
struct Int32Vect3 neutral
Neutral values, compensation on unscaled->scaled.
Definition: imu.h:66
struct Int32Vect3 unscaled
Last unscaled values in sensor frame.
Definition: imu.h:75
#define IMU_MAX_SENSORS
Definition: imu.h:37
struct imu_calib_t calibrated
Calibration bitmask.
Definition: imu.h:50
uint8_t accel_abi_send_id
Filter out and send only a specific ABI id in telemetry for the accelerometer.
Definition: imu.h:91
struct Int32Vect3 scaled
Last scaled values in body frame.
Definition: imu.h:74
bool rotation
Rotation calibrated.
Definition: imu.h:43
uint8_t gyro_abi_send_id
Filter out and send only a specific ABI id in telemetry for the gyro.
Definition: imu.h:90
uint8_t abi_id
ABI sensor ID.
Definition: imu.h:60
abstract IMU interface providing fixed point interface
Definition: imu.h:84
Definition: imu.h:47
Definition: imu.h:71
static float p[2][2]
PRINT_CONFIG_MSG("USE_INS_NAV_INIT defaulting to TRUE")
static TRICAL_instance_t mag_calib
API to get/set the generic vehicle states.
static const struct usb_device_descriptor dev
Definition: usb_ser_hw.c:74
int8_t register_periodic_telemetry(struct periodic_telemetry *_pt, uint8_t _id, telemetry_cb _cb)
Register a telemetry callback function.
Definition: telemetry.c:51
Periodic telemetry system header (includes downlink utility and generated code).
#define DefaultPeriodic
Set default periodic telemetry.
Definition: telemetry.h:66
unsigned short uint16_t
Typedef defining 16 bit unsigned short type.
Definition: vl53l1_types.h:88
int int32_t
Typedef defining 32 bit int type.
Definition: vl53l1_types.h:83
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