Paparazzi UAS v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
Loading...
Searching...
No Matches
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}
59PRINT_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}}
64PRINT_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}
94PRINT_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}}
99PRINT_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}
129PRINT_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}}
134PRINT_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
157
158
159#ifndef IMU_GYRO_ABI_SEND_ID
160#define IMU_GYRO_ABI_SEND_ID ABI_BROADCAST
161#endif
163
164
165#ifndef IMU_ACCEL_ABI_SEND_ID
166#define IMU_ACCEL_ABI_SEND_ID ABI_BROADCAST
167#endif
169
170
171#ifndef IMU_MAG_ABI_SEND_ID
172#define IMU_MAG_ABI_SEND_ID ABI_BROADCAST
173#endif
175
176
177#ifndef IMU_LOG_HIGHSPEED_DEVICE
178#define IMU_LOG_HIGHSPEED_DEVICE flightrecorder_sdlog
179#endif
180
181
182#if PERIODIC_TELEMETRY
184
185static void send_accel_raw(struct transport_tx *trans, struct link_device *dev)
186{
188 return;
189 static uint8_t id = 0;
193 return;
194 id++;
195 if(id >= IMU_MAX_SENSORS || imu.accels[id].abi_id == ABI_DISABLE)
196 id = 0;
197}
198
199static void send_accel_scaled(struct transport_tx *trans, struct link_device *dev)
200{
202 return;
203 static uint8_t id = 0;
205 &imu.accels[id].scaled.x, &imu.accels[id].scaled.y, &imu.accels[id].scaled.z);
207 return;
208 id++;
209 if(id >= IMU_MAX_SENSORS || imu.accels[id].abi_id == ABI_DISABLE)
210 id = 0;
211}
212
213static void send_accel(struct transport_tx *trans, struct link_device *dev)
214{
216 return;
217 static uint8_t id = 0;
218 struct FloatVect3 accel_float;
223 return;
224 id++;
225 if(id >= IMU_MAX_SENSORS || imu.accels[id].abi_id == ABI_DISABLE)
226 id = 0;
227}
228
229static void send_gyro_raw(struct transport_tx *trans, struct link_device *dev)
230{
232 return;
233 static uint8_t id = 0;
235 &imu.gyros[id].unscaled.p, &imu.gyros[id].unscaled.q, &imu.gyros[id].unscaled.r);
237 return;
238 id++;
239 if(id >= IMU_MAX_SENSORS || imu.gyros[id].abi_id == ABI_DISABLE)
240 id = 0;
241}
242
243static void send_gyro_scaled(struct transport_tx *trans, struct link_device *dev)
244{
246 return;
247 static uint8_t id = 0;
249 &imu.gyros[id].scaled.p, &imu.gyros[id].scaled.q, &imu.gyros[id].scaled.r);
251 return;
252 id++;
253 if(id >= IMU_MAX_SENSORS || imu.gyros[id].abi_id == ABI_DISABLE)
254 id = 0;
255}
256
257static void send_gyro(struct transport_tx *trans, struct link_device *dev)
258{
260 return;
261 static uint8_t id = 0;
262 struct FloatRates gyro_float;
265 &gyro_float.p, &gyro_float.q, &gyro_float.r);
267 return;
268 id++;
269 if(id >= IMU_MAX_SENSORS || imu.gyros[id].abi_id == ABI_DISABLE)
270 id = 0;
271}
272
273static void send_mag_raw(struct transport_tx *trans, struct link_device *dev)
274{
276 return;
277 static uint8_t id = 0;
279 &imu.mags[id].unscaled.x, &imu.mags[id].unscaled.y, &imu.mags[id].unscaled.z);
281 return;
282 id++;
283 if(id >= IMU_MAX_SENSORS || imu.mags[id].abi_id == ABI_DISABLE)
284 id = 0;
285}
286
287static void send_mag_scaled(struct transport_tx *trans, struct link_device *dev)
288{
290 return;
291 static uint8_t id = 0;
293 &imu.mags[id].scaled.x, &imu.mags[id].scaled.y, &imu.mags[id].scaled.z);
295 return;
296 id++;
297 if(id >= IMU_MAX_SENSORS || imu.mags[id].abi_id == ABI_DISABLE)
298 id = 0;
299}
300
301static void send_mag(struct transport_tx *trans, struct link_device *dev)
302{
304 return;
305 static uint8_t id = 0;
306 struct FloatVect3 mag_float;
311 return;
312 id++;
313 if(id >= IMU_MAX_SENSORS || imu.mags[id].abi_id == ABI_DISABLE)
314 id = 0;
315}
316
317static void send_mag_current(struct transport_tx *trans, struct link_device *dev)
318{
320 return;
321 static uint8_t id = 0;
323 &imu.mags[id].abi_id,
324 &imu.mags[id].unscaled.x,
325 &imu.mags[id].unscaled.y,
326 &imu.mags[id].unscaled.z,
329 return;
330 id++;
331 if(id >= IMU_MAX_SENSORS || imu.mags[id].abi_id == ABI_DISABLE)
332 id = 0;
333}
334
335#endif /* PERIODIC_TELEMETRY */
336
337#if USE_SHELL
338#include "modules/core/shell.h"
339#include "printf.h"
340#include "string.h"
341
342static void show_calibrated(shell_stream_t *sh, struct imu_calib_t *calibrated) {
343 chprintf(sh, " calibrated: neutral %d, scale %d, rotation %d, current %d, filter %d\r\n",
344 calibrated->neutral, calibrated->scale, calibrated->rotation, calibrated->current, calibrated->filter);
345}
346
347static void show_vect3(shell_stream_t *sh, char* name, struct Int32Vect3 *v) {
348 chprintf(sh, " %s: %ld, %ld, %ld\r\n", name, v->x, v->y, v->z);
349}
350
351static void show_rates(shell_stream_t *sh, char* name, struct Int32Rates *r) {
352 chprintf(sh, " %s: %ld, %ld, %ld\r\n", name, r->p, r->q, r->r);
353}
354
355static void show_matrix(shell_stream_t *sh, char* name, struct Int32RMat *m) {
356 chprintf(sh, " %s:\r\n", name);
357 chprintf(sh, " %ld, %ld, %ld\r\n", MAT33_ELMT(*m, 0, 0), MAT33_ELMT(*m, 0, 1), MAT33_ELMT(*m, 0, 2));
358 chprintf(sh, " %ld, %ld, %ld\r\n", MAT33_ELMT(*m, 1, 0), MAT33_ELMT(*m, 1, 1), MAT33_ELMT(*m, 1, 2));
359 chprintf(sh, " %ld, %ld, %ld\r\n", MAT33_ELMT(*m, 2, 0), MAT33_ELMT(*m, 2, 1), MAT33_ELMT(*m, 2, 2));
360}
361
362static void cmd_imu(shell_stream_t *sh, int argc, const char *const argv[])
363{
364 (void) argv;
365 int i = 0;
366 if (argc > 0) {
367 chprintf(sh, "Usage: imu\r\n");
368 return;
369 }
370 chprintf(sh, "GYRO IMU data\r\n");
371 for (i = 0; i < IMU_MAX_SENSORS; i++) {
372 if (imu.gyros[i].abi_id != 0) {
373 chprintf(sh, " Gyro id: %u, time %lu\r\n", imu.gyros[i].abi_id, imu.gyros[i].last_stamp);
375 show_rates(sh, "neutral", &imu.gyros[i].neutral);
376 show_rates(sh, "scale_num", &imu.gyros[i].scale[0]);
377 show_rates(sh, "scale_den", &imu.gyros[i].scale[1]);
378 show_matrix(sh, "body_to_sensor", &imu.gyros[i].body_to_sensor);
379 show_rates(sh, "unscaled", &imu.gyros[i].unscaled);
380 show_rates(sh, "scaled", &imu.gyros[i].scaled);
381 struct FloatRates gf;
383 chprintf(sh, " -> gyro (rad/s): %.3f, %.3f, %.3f\r\n", gf.p, gf.q, gf.r);
384 }
385 }
386 chprintf(sh, "ACCEL IMU data\r\n");
387 for (i = 0; i < IMU_MAX_SENSORS; i++) {
388 if (imu.accels[i].abi_id != 0) {
389 chprintf(sh, " Accel id: %u, time %lu\r\n", imu.accels[i].abi_id, imu.accels[i].last_stamp);
391 show_vect3(sh, "neutral", &imu.accels[i].neutral);
392 show_vect3(sh, "scale_num", &imu.accels[i].scale[0]);
393 show_vect3(sh, "scale_den", &imu.accels[i].scale[1]);
394 show_matrix(sh, "body_to_sensor", &imu.accels[i].body_to_sensor);
395 show_vect3(sh, "unscaled", &imu.accels[i].unscaled);
396 show_vect3(sh, "scaled", &imu.accels[i].scaled);
397 struct FloatVect3 af;
399 chprintf(sh, " -> accel (m/s2): %.3f, %.3f, %.3f\r\n", af.x, af.y, af.z);
400 }
401 }
402 chprintf(sh, "MAG IMU data\r\n");
403 for (i = 0; i < IMU_MAX_SENSORS; i++) {
404 if (imu.mags[i].abi_id != 0) {
405 chprintf(sh, " Mag id: %u\r\n", imu.mags[i].abi_id);
407 show_vect3(sh, "neutral", &imu.mags[i].neutral);
408 show_vect3(sh, "scale_num", &imu.mags[i].scale[0]);
409 show_vect3(sh, "scale_den", &imu.mags[i].scale[1]);
410 show_matrix(sh, "body_to_sensor", &imu.mags[i].body_to_sensor);
411 show_vect3(sh, "unscaled", &imu.mags[i].unscaled);
412 show_vect3(sh, "scaled", &imu.mags[i].scaled);
413 struct FloatVect3 mf;
415 chprintf(sh, " -> mag (unit): %.3f, %.3f, %.3f\r\n", mf.x, mf.y, mf.z);
416 }
417 }
418}
419
420#endif
421
422struct Imu imu = {0};
424static void imu_gyro_raw_cb(uint8_t sender_id, uint32_t stamp, struct Int32Rates *data, uint8_t samples, float rate, float temp);
425static void imu_accel_raw_cb(uint8_t sender_id, uint32_t stamp, struct Int32Vect3 *data, uint8_t samples, float rate, float temp);
426static void imu_mag_raw_cb(uint8_t sender_id, uint32_t stamp, struct Int32Vect3 *data);
428
429void imu_init(void)
430{
431 // Set the Body to IMU rotation
434 struct Int32RMat *body_to_imu_rmat = orientationGetRMat_i(&imu.body_to_imu);
435
436
437 // Set the calibrated sensors
438 struct Int32RMat body_to_sensor;
439 const struct imu_gyro_t gyro_calib[] = IMU_GYRO_CALIB;
440 const struct imu_accel_t accel_calib[] = IMU_ACCEL_CALIB;
441 const struct imu_mag_t mag_calib[] = IMU_MAG_CALIB;
442 const uint8_t gyro_calib_len = sizeof(gyro_calib) / sizeof(struct imu_gyro_t);
443 const uint8_t accel_calib_len = sizeof(accel_calib) / sizeof(struct imu_accel_t);
444 const uint8_t mag_calib_len = sizeof(mag_calib) / sizeof(struct imu_mag_t);
445
446 // Initialize the sensors to default values
447 for(uint8_t i = 0; i < IMU_MAX_SENSORS; i++) {
448 /* Copy gyro calibration if needed */
449 if(i >= gyro_calib_len) {
451 imu.gyros[i].calibrated.neutral = false;
452 imu.gyros[i].calibrated.scale = false;
453 imu.gyros[i].calibrated.rotation = false;
454 imu.gyros[i].calibrated.filter = false;
455 } else {
456 imu.gyros[i] = gyro_calib[i];
457 }
458
459 // Set the default safe values if not calibrated
460 if(!imu.gyros[i].calibrated.neutral) {
462 }
463 if(!imu.gyros[i].calibrated.scale) {
465 RATES_ASSIGN(imu.gyros[i].scale[1], 1, 1, 1);
466 }
467 if(!imu.gyros[i].calibrated.rotation) {
469 }
470 imu.gyros[i].last_stamp = 0;
471 int32_rmat_comp(&body_to_sensor, body_to_imu_rmat, &imu.gyros[i].body_to_sensor);
473
474 if(imu.gyros[i].calibrated.filter) {
475 float tau = 1.0 / (2.0 * M_PI * imu.gyros[i].filter_freq);
477 for(uint8_t j = 0; j < 3; j++)
479 }
480
481 /* Copy accel calibration if needed */
482 if(i >= accel_calib_len) {
484 imu.accels[i].calibrated.neutral = false;
485 imu.accels[i].calibrated.scale = false;
486 imu.accels[i].calibrated.rotation = false;
487 imu.accels[i].calibrated.filter = false;
488 } else {
489 imu.accels[i] = accel_calib[i];
490 }
491
492 // Set the default safe values if not calibrated
493 if(!imu.accels[i].calibrated.neutral) {
495 }
496 if(!imu.accels[i].calibrated.scale) {
498 VECT3_ASSIGN(imu.accels[i].scale[1], 1, 1, 1);
499 }
500 if(!imu.accels[i].calibrated.rotation) {
502 }
503 imu.accels[i].last_stamp = 0;
504 int32_rmat_comp(&body_to_sensor, body_to_imu_rmat, &imu.accels[i].body_to_sensor);
506
507 if(imu.accels[i].calibrated.filter) {
508 float tau = 1.0 / (2.0 * M_PI * imu.accels[i].filter_freq);
510 for(uint8_t j = 0; j < 3; j++)
512 }
513
514 /* Copy mag calibrated if needed */
515 if(i >= mag_calib_len) {
517 imu.mags[i].calibrated.neutral = false;
518 imu.mags[i].calibrated.scale = false;
519 imu.mags[i].calibrated.rotation = false;
520 imu.mags[i].calibrated.current = false;
521 } else {
522 imu.mags[i] = mag_calib[i];
523 }
524
525 // Set the default safe values if not calibrated
526 if(!imu.mags[i].calibrated.neutral) {
528 }
529 if(!imu.mags[i].calibrated.scale) {
531 VECT3_ASSIGN(imu.mags[i].scale[1], 1, 1, 1);
532 }
533 if(!imu.mags[i].calibrated.rotation) {
535 }
536 if(!imu.mags[i].calibrated.current) {
538 }
539 int32_rmat_comp(&body_to_sensor, body_to_imu_rmat, &imu.mags[i].body_to_sensor);
541 }
542
543 // Bind to raw measurements
547
548#if PERIODIC_TELEMETRY
559#endif // DOWNLINK
560
561#if USE_SHELL
562 shell_add_entry("imu", cmd_imu);
563#endif
564
565 // Set defaults
569 imu.initialized = true;
570}
571
581{
582 // Find the correct gyro
583 struct imu_gyro_t *gyro = imu_get_gyro(abi_id, true);
584 if(gyro == NULL)
585 return;
586
587 // Copy the defaults
588 if(imu_to_sensor != NULL && !gyro->calibrated.rotation) {
589 struct Int32RMat body_to_sensor;
590 struct Int32RMat *body_to_imu = orientationGetRMat_i(&imu.body_to_imu);
591 int32_rmat_comp(&body_to_sensor, body_to_imu, imu_to_sensor);
592 RMAT_COPY(gyro->body_to_sensor, body_to_sensor);
593 }
594 if(neutral != NULL && !gyro->calibrated.neutral)
595 RATES_COPY(gyro->neutral, *neutral);
596 if(scale != NULL && !gyro->calibrated.scale) {
598 RATES_COPY(gyro->scale[1], scale[1]);
599 }
600}
601
610void imu_set_defaults_accel(uint8_t abi_id, const struct Int32RMat *imu_to_sensor, const struct Int32Vect3 *neutral, const struct Int32Vect3 *scale)
611{
612 // Find the correct accel
613 struct imu_accel_t *accel = imu_get_accel(abi_id, true);
614 if(accel == NULL)
615 return;
616
617 // Copy the defaults
618 if(imu_to_sensor != NULL && !accel->calibrated.rotation) {
619 struct Int32RMat body_to_sensor;
620 struct Int32RMat *body_to_imu = orientationGetRMat_i(&imu.body_to_imu);
621 int32_rmat_comp(&body_to_sensor, body_to_imu, imu_to_sensor);
622 RMAT_COPY(accel->body_to_sensor, body_to_sensor);
623 }
624 if(neutral != NULL && !accel->calibrated.neutral)
625 VECT3_COPY(accel->neutral, *neutral);
626 if(scale != NULL && !accel->calibrated.scale) {
628 VECT3_COPY(accel->scale[1], scale[1]);
629 }
630}
631
640void imu_set_defaults_mag(uint8_t abi_id, const struct Int32RMat *imu_to_sensor, const struct Int32Vect3 *neutral, const struct Int32Vect3 *scale)
641{
642 // Find the correct mag
643 struct imu_mag_t *mag = imu_get_mag(abi_id, true);
644 if(mag == NULL)
645 return;
646
647 // Copy the defaults
648 if(imu_to_sensor != NULL && !mag->calibrated.rotation) {
649 struct Int32RMat body_to_sensor;
650 struct Int32RMat *body_to_imu = orientationGetRMat_i(&imu.body_to_imu);
651 int32_rmat_comp(&body_to_sensor, body_to_imu, imu_to_sensor);
652 RMAT_COPY(mag->body_to_sensor, body_to_sensor);
653 }
654 if(neutral != NULL && !mag->calibrated.neutral)
655 VECT3_COPY(mag->neutral, *neutral);
656 if(scale != NULL && !mag->calibrated.scale) {
658 VECT3_COPY(mag->scale[1], scale[1]);
659 }
660}
661
662static void imu_gyro_raw_cb(uint8_t sender_id, uint32_t stamp, struct Int32Rates *data, uint8_t samples, float rate, float temp)
663{
664 // Find the correct gyro
665 struct imu_gyro_t *gyro = imu_get_gyro(sender_id, true);
666 if(gyro == NULL || samples < 1)
667 return;
668
669 // Filter the gyro
671 if(gyro->calibrated.filter) {
672 for(uint8_t i = 0; i < samples; i++) {
673 data_filtered[i].p = update_butterworth_2_low_pass(&gyro->filter[0], data[i].p);
674 data_filtered[i].q = update_butterworth_2_low_pass(&gyro->filter[1], data[i].q);
675 data_filtered[i].r = update_butterworth_2_low_pass(&gyro->filter[2], data[i].r);
676 }
677 data = data_filtered;
678 }
679
680 // Copy last sample as unscaled
681 RATES_COPY(gyro->unscaled, data[samples-1]);
682
683 // Scale the gyro
684 struct Int32Rates scaled, scaled_rot;
685 scaled.p = (gyro->unscaled.p - gyro->neutral.p) * gyro->scale[0].p / gyro->scale[1].p;
686 scaled.q = (gyro->unscaled.q - gyro->neutral.q) * gyro->scale[0].q / gyro->scale[1].q;
687 scaled.r = (gyro->unscaled.r - gyro->neutral.r) * gyro->scale[0].r / gyro->scale[1].r;
688
689 // Rotate the sensor
691
692#if IMU_INTEGRATION
693 // Only integrate if we have gotten a previous measurement and didn't overflow the timer
694 if(!isnan(rate) && gyro->last_stamp > 0 && stamp > gyro->last_stamp) {
695 struct FloatRates integrated;
696
697 // Trapezoidal integration (TODO: coning correction)
698 integrated.p = RATE_FLOAT_OF_BFP(gyro->scaled.p + scaled_rot.p) * 0.5f;
699 integrated.q = RATE_FLOAT_OF_BFP(gyro->scaled.q + scaled_rot.q) * 0.5f;
700 integrated.r = RATE_FLOAT_OF_BFP(gyro->scaled.r + scaled_rot.r) * 0.5f;
701
702 // Only perform multiple integrations in sensor frame if needed
703 if(samples > 1) {
705 struct FloatRMat body_to_sensor;
706 // Rotate back to sensor frame
707 RMAT_FLOAT_OF_BFP(body_to_sensor, gyro->body_to_sensor);
708 float_rmat_ratemult(&integrated_sensor, &body_to_sensor, &integrated);
709
710 // Add all the other samples
711 for(uint8_t i = 0; i < samples-1; i++) {
712 struct FloatRates f_sample;
713 f_sample.p = RATE_FLOAT_OF_BFP((data[i].p - gyro->neutral.p) * gyro->scale[0].p / gyro->scale[1].p);
714 f_sample.q = RATE_FLOAT_OF_BFP((data[i].q - gyro->neutral.q) * gyro->scale[0].q / gyro->scale[1].q);
715 f_sample.r = RATE_FLOAT_OF_BFP((data[i].r - gyro->neutral.r) * gyro->scale[0].r / gyro->scale[1].r);
716
717#if IMU_LOG_HIGHSPEED
719#endif
720
724 }
725
726 // Rotate to body frame
727 float_rmat_transp_ratemult(&integrated, &body_to_sensor, &integrated_sensor);
728 }
729
730 // Divide by the time of the collected samples
731 integrated.p = integrated.p * (1.f / rate);
732 integrated.q = integrated.q * (1.f / rate);
733 integrated.r = integrated.r * (1.f / rate);
734
735 // Send the integrated values
736 uint16_t dt = (1e6 / rate) * samples;
737 AbiSendMsgIMU_GYRO_INT(sender_id, stamp, &integrated, dt);
738 }
739#else
740 (void)rate; // Surpress compile warning not used
741#endif
742
743#if IMU_LOG_HIGHSPEED
744 struct FloatRates f_sample;
747#endif
748
749 // Copy and send
750 gyro->temperature = temp;
753 gyro->last_stamp = stamp;
754}
755
756static void imu_accel_raw_cb(uint8_t sender_id, uint32_t stamp, struct Int32Vect3 *data, uint8_t samples, float rate, float temp)
757{
758 // Find the correct accel
759 struct imu_accel_t *accel = imu_get_accel(sender_id, true);
760 if(accel == NULL || samples < 1)
761 return;
762
763 // Filter the accel
765 if(accel->calibrated.filter) {
766 for(uint8_t i = 0; i < samples; i++) {
767 data_filtered[i].x = update_butterworth_2_low_pass(&accel->filter[0], data[i].x);
768 data_filtered[i].y = update_butterworth_2_low_pass(&accel->filter[1], data[i].y);
769 data_filtered[i].z = update_butterworth_2_low_pass(&accel->filter[2], data[i].z);
770 }
771 data = data_filtered;
772 }
773
774 // Copy last sample as unscaled
775 VECT3_COPY(accel->unscaled, data[samples-1]);
776
777 // Scale the accel
778 struct Int32Vect3 scaled, scaled_rot;
779 scaled.x = (accel->unscaled.x - accel->neutral.x) * accel->scale[0].x / accel->scale[1].x;
780 scaled.y = (accel->unscaled.y - accel->neutral.y) * accel->scale[0].y / accel->scale[1].y;
781 scaled.z = (accel->unscaled.z - accel->neutral.z) * accel->scale[0].z / accel->scale[1].z;
782
783 // Rotate the sensor
785
786#if IMU_INTEGRATION
787 // Only integrate if we have gotten a previous measurement and didn't overflow the timer
788 if(!isnan(rate) && accel->last_stamp > 0 && stamp > accel->last_stamp) {
789 struct FloatVect3 integrated;
790
791 // Trapezoidal integration
792 integrated.x = ACCEL_FLOAT_OF_BFP(accel->scaled.x + scaled_rot.x) * 0.5f;
793 integrated.y = ACCEL_FLOAT_OF_BFP(accel->scaled.y + scaled_rot.y) * 0.5f;
794 integrated.z = ACCEL_FLOAT_OF_BFP(accel->scaled.z + scaled_rot.z) * 0.5f;
795
796 // Only perform multiple integrations in sensor frame if needed
797 if(samples > 1) {
799 struct FloatRMat body_to_sensor;
800 // Rotate back to sensor frame
801 RMAT_FLOAT_OF_BFP(body_to_sensor, accel->body_to_sensor);
802 float_rmat_vmult(&integrated_sensor, &body_to_sensor, &integrated);
803
804 // Add all the other samples
805 for(uint8_t i = 0; i < samples-1; i++) {
806 struct FloatVect3 f_sample;
807 f_sample.x = ACCEL_FLOAT_OF_BFP((data[i].x - accel->neutral.x) * accel->scale[0].x / accel->scale[1].x);
808 f_sample.y = ACCEL_FLOAT_OF_BFP((data[i].y - accel->neutral.y) * accel->scale[0].y / accel->scale[1].y);
809 f_sample.z = ACCEL_FLOAT_OF_BFP((data[i].z - accel->neutral.z) * accel->scale[0].z / accel->scale[1].z);
810
811#if IMU_LOG_HIGHSPEED
813#endif
814
818 }
819
820 // Rotate to body frame
821 float_rmat_transp_vmult(&integrated, &body_to_sensor, &integrated_sensor);
822 }
823
824 // Divide by the time of the collected samples
825 integrated.x = integrated.x * (1.f / rate);
826 integrated.y = integrated.y * (1.f / rate);
827 integrated.z = integrated.z * (1.f / rate);
828
829 // Send the integrated values
830 uint16_t dt = (1e6 / rate) * samples;
831 AbiSendMsgIMU_ACCEL_INT(sender_id, stamp, &integrated, dt);
832 }
833#else
834 (void)rate; // Surpress compile warning not used
835#endif
836
837#if IMU_LOG_HIGHSPEED
838 struct FloatVect3 f_sample;
841#endif
842
843 // Copy and send
844 accel->temperature = temp;
847 accel->last_stamp = stamp;
848}
849
851{
852 // Find the correct mag
853 struct imu_mag_t *mag = imu_get_mag(sender_id, true);
854 if(mag == NULL)
855 return;
856
857 // Calculate current compensation
862
863 // Copy last sample as unscaled
864 VECT3_COPY(mag->unscaled, *data);
865
866 // Scale the mag
867 struct Int32Vect3 scaled;
868 scaled.x = (mag->unscaled.x - mag_correction.x - mag->neutral.x) * mag->scale[0].x / mag->scale[1].x;
869 scaled.y = (mag->unscaled.y - mag_correction.y - mag->neutral.y) * mag->scale[0].y / mag->scale[1].y;
870 scaled.z = (mag->unscaled.z - mag_correction.z - mag->neutral.z) * mag->scale[0].z / mag->scale[1].z;
871
872 // Rotate the sensor
873 int32_rmat_transp_vmult(&mag->scaled, &mag->body_to_sensor, &scaled);
875}
876
885 // Find the correct gyro or create index
886 // If abi_id was set to broadcast (assuming a single IMU case), the first request takes the index for himself
887 struct imu_gyro_t *gyro = NULL;
888 for(uint8_t i = 0; i < IMU_MAX_SENSORS; i++) {
889 if(imu.gyros[i].abi_id == sender_id || (create && (imu.gyros[i].abi_id == ABI_BROADCAST || imu.gyros[i].abi_id == ABI_DISABLE))) {
890 gyro = &imu.gyros[i];
891 gyro->abi_id = sender_id;
892 break;
893 } else if(sender_id == ABI_BROADCAST && imu.gyros[i].abi_id != ABI_DISABLE) {
894 gyro = &imu.gyros[i];
895 }
896 }
897 return gyro;
898}
899
908 // Find the correct accel
909 // If abi_id was set to broadcast (assuming a single IMU case), the first request takes the index for himself
910 struct imu_accel_t *accel = NULL;
911 for(uint8_t i = 0; i < IMU_MAX_SENSORS; i++) {
913 accel = &imu.accels[i];
914 accel->abi_id = sender_id;
915 break;
916 } else if(sender_id == ABI_BROADCAST && imu.accels[i].abi_id != ABI_DISABLE) {
917 accel = &imu.accels[i];
918 }
919 }
920
921 return accel;
922}
923
932 // Find the correct mag
933 // If abi_id was set to broadcast (assuming a single IMU case), the first request takes the index for himself
934 struct imu_mag_t *mag = NULL;
935 for(uint8_t i = 0; i < IMU_MAX_SENSORS; i++) {
936 if(imu.mags[i].abi_id == sender_id || (create && (imu.mags[i].abi_id == ABI_BROADCAST || imu.mags[i].abi_id == ABI_DISABLE))) {
937 mag = &imu.mags[i];
938 mag->abi_id = sender_id;
939 break;
940 } else if(sender_id == ABI_BROADCAST && imu.mags[i].abi_id != ABI_DISABLE) {
941 mag = &imu.mags[i];
942 }
943 }
944
945 return mag;
946}
947
981
989
997
1005
1007{
1008 imu.b2i_set_current = set;
1009
1010 if (imu.b2i_set_current) {
1011 // adjust imu_to_body roll and pitch by current NedToBody roll and pitch
1014 if (stateIsAttitudeValid()) {
1015 // adjust imu_to_body roll and pitch by current NedToBody roll and pitch
1019 } else {
1020 // indicate that we couldn't set to current roll/pitch
1021 imu.b2i_set_current = false;
1022 }
1023 } else {
1024 // reset to BODY_TO_IMU as defined in airframe file
1027 }
1028}
1029
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:92
Interface for electrical status: supply voltage, current, battery status, etc.
float current
current in A
Definition electrical.h:47
void chprintf(BaseSequentialStream *lchp, const char *fmt,...)
Definition printf.c:395
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)
#define RATES_COPY(_a, _b)
#define RATES_ASSIGN(_ra, _p, _q, _r)
#define EULERS_BFP_OF_REAL(_ei, _ef)
#define RMAT_FLOAT_OF_BFP(_ef, _ei)
#define RMAT_COPY(_o, _i)
#define VECT3_ASSIGN(_a, _x, _y, _z)
#define VECT3_COPY(_a, _b)
#define RATES_FLOAT_OF_BFP(_rf, _ri)
#define MAT33_ELMT(_m, _row, _col)
#define ACCELS_FLOAT_OF_BFP(_ef, _ei)
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 void orientationSetEulers_f(struct OrientationReps *orientation, struct FloatEulers *eulers)
Set vehicle body attitude from euler angles (float).
static struct Int32RMat * orientationGetRMat_i(struct OrientationReps *orientation)
Get vehicle body attitude rotation matrix (int).
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:1224
static struct FloatEulers * stateGetNedToBodyEulers_f(void)
Get vehicle body attitude euler angles (float).
Definition state.h:1306
#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
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:662
#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:273
#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
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
static abi_event imu_accel_raw_ev
Definition imu.c:423
static abi_event imu_mag_raw_ev
Definition imu.c:423
#define IMU_MAG_X_SIGN
By default mag signs are positive for single IMU with old format and defaults.
Definition imu.c:117
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
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
void imu_SetBodyToImuTheta(float theta)
Definition imu.c:990
#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:756
#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:610
#define IMU_LOG_HIGHSPEED_DEVICE
By default log highspeed on the flightrecorder.
Definition imu.c:178
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:953
static void send_mag_scaled(struct transport_tx *trans, struct link_device *dev)
Definition imu.c:287
static void send_mag_current(struct transport_tx *trans, struct link_device *dev)
Definition imu.c:317
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
#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:429
void imu_SetBodyToImuPsi(float psi)
Definition imu.c:998
static abi_event imu_gyro_raw_ev
Definition imu.c:423
static void send_accel_raw(struct transport_tx *trans, struct link_device *dev)
Definition imu.c:185
#define IMU_GYRO_R_SIGN
Definition imu.c:53
void imu_SetBodyToImuCurrent(float set)
Definition imu.c:1006
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
static void send_gyro_scaled(struct transport_tx *trans, struct link_device *dev)
Definition imu.c:243
static void send_gyro(struct transport_tx *trans, struct link_device *dev)
Definition imu.c:257
void imu_SetBodyToImuPhi(float phi)
Definition imu.c:982
static void send_accel(struct transport_tx *trans, struct link_device *dev)
Definition imu.c:213
static void imu_mag_raw_cb(uint8_t sender_id, uint32_t stamp, struct Int32Vect3 *data)
Definition imu.c:850
#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:199
static void send_mag(struct transport_tx *trans, struct link_device *dev)
Definition imu.c:301
static void send_gyro_raw(struct transport_tx *trans, struct link_device *dev)
Definition imu.c:229
#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: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 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
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
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
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
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
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
struct Int32RMat body_to_sensor
Rotation from body to sensor frame (body to imu combined with imu to sensor)
Definition imu.h:58
struct Int32Rates unscaled
Last unscaled values in sensor frame.
Definition imu.h:54
uint8_t abi_id
ABI sensor ID.
Definition imu.h:80
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
#define IMU_MAX_SENSORS
Definition imu.h:38
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
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
static float p[2][2]
PRINT_CONFIG_MSG("USE_INS_NAV_INIT defaulting to TRUE")
static void init_butterworth_2_low_pass(Butterworth2LowPass *filter, float tau, float sample_time, float value)
Init a second order Butterworth filter.
static float update_butterworth_2_low_pass(Butterworth2LowPass *filter, float value)
Update second order Butterworth low pass filter state with a new value.
static TRICAL_instance_t mag_calib
uint16_t foo
Definition main_demo5.c:58
PRINT_CONFIG_VAR(ONELOOP_ANDI_FILT_CUTOFF)
struct pprzlog_transport pprzlog_tp
PPRZLOG transport structure.
Definition pprzlog_tp.c:29
Mini printf-like functionality.
void shell_add_entry(char *cmd_name, shell_cmd_t *cmd)
Add dynamic entry.
Definition shell_arch.c:92
BaseSequentialStream shell_stream_t
Definition shell_arch.h:31
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.
int int32_t
Typedef defining 32 bit int type.
unsigned int uint32_t
Typedef defining 32 bit unsigned int type.
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.