-
Notifications
You must be signed in to change notification settings - Fork 1.1k
/
imu.c
939 lines (830 loc) · 36.5 KB
/
imu.c
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
/*
* Copyright (C) 2008-2022 The Paparazzi Team
* Freek van Tienen <freek.v.tienen@gmail.com>
*
* This file is part of paparazzi.
*
* paparazzi is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2, or (at your option)
* any later version.
*
* paparazzi is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with paparazzi; see the file COPYING. If not, write to
* the Free Software Foundation, 59 Temple Place - Suite 330,
* Boston, MA 02111-1307, USA.
*/
/**
* @file modules/imu/imu.c
* Inertial Measurement Unit interface.
*/
#ifdef BOARD_CONFIG
#include BOARD_CONFIG
#endif
#include "modules/imu/imu.h"
#include "state.h"
#include "modules/core/abi.h"
#include "modules/energy/electrical.h"
/** By default disable IMU integration calculations */
#ifndef IMU_INTEGRATION
#define IMU_INTEGRATION false
#endif
/** By default gyro signs are positive for single IMU with old format or defaults */
#if defined(IMU_GYRO_CALIB) && (defined(IMU_GYRO_P_SIGN) || defined(IMU_GYRO_Q_SIGN) || defined(IMU_GYRO_R_SIGN))
#warning "The IMU_GYRO_?_SIGN's aren't compatible with the IMU_GYRO_CALIB define in the airframe"
#endif
#ifndef IMU_GYRO_P_SIGN
#define IMU_GYRO_P_SIGN 1
#endif
#ifndef IMU_GYRO_Q_SIGN
#define IMU_GYRO_Q_SIGN 1
#endif
#ifndef IMU_GYRO_R_SIGN
#define IMU_GYRO_R_SIGN 1
#endif
/** Default gyro calibration is for single IMU with old format */
#if defined(IMU_GYRO_P_NEUTRAL) || defined(IMU_GYRO_Q_NEUTRAL) || defined(IMU_GYRO_R_NEUTRAL)
#define GYRO_NEUTRAL {IMU_GYRO_P_NEUTRAL, IMU_GYRO_Q_NEUTRAL, IMU_GYRO_R_NEUTRAL}
PRINT_CONFIG_MSG("Using single IMU gyro neutral calibration")
#endif
#if defined(IMU_GYRO_P_SENS) || defined(IMU_GYRO_Q_SENS) || defined(IMU_GYRO_R_SENS)
#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}}
PRINT_CONFIG_MSG("Using single IMU gyro sensitivity calibration")
#endif
#if defined(GYRO_NEUTRAL) && defined(GYRO_SCALE)
#define IMU_GYRO_CALIB {{.abi_id=ABI_BROADCAST, .calibrated={.neutral=true, .scale=true}, .neutral=GYRO_NEUTRAL, .scale=GYRO_SCALE}}
#elif defined(GYRO_NEUTRAL)
#define IMU_GYRO_CALIB {{.abi_id=ABI_BROADCAST, .calibrated={.neutral=true}, .neutral=GYRO_NEUTRAL}}
#elif defined(GYRO_SCALE)
#define IMU_GYRO_CALIB {{.abi_id=ABI_BROADCAST, .calibrated={.scale=true}, .scale=GYRO_SCALE}}
#elif !defined(IMU_GYRO_CALIB)
#define IMU_GYRO_CALIB {}
#endif
/** By default accel signs are positive for single IMU with old format and defaults */
#if defined(IMU_ACCEL_CALIB) && (defined(IMU_ACCEL_X_SIGN) || defined(IMU_ACCEL_Y_SIGN) || defined(IMU_ACCEL_Z_SIGN))
#warning "The IMU_ACCEL_?_SIGN's aren't compatible with the IMU_ACCEL_CALIB define in the airframe"
#endif
#ifndef IMU_ACCEL_X_SIGN
#define IMU_ACCEL_X_SIGN 1
#endif
#ifndef IMU_ACCEL_Y_SIGN
#define IMU_ACCEL_Y_SIGN 1
#endif
#ifndef IMU_ACCEL_Z_SIGN
#define IMU_ACCEL_Z_SIGN 1
#endif
/** Default accel calibration is for single IMU with old format */
#if defined(IMU_ACCEL_X_NEUTRAL) || defined(IMU_ACCEL_Y_NEUTRAL) || defined(IMU_ACCEL_Z_NEUTRAL)
#define ACCEL_NEUTRAL {IMU_ACCEL_X_NEUTRAL, IMU_ACCEL_Y_NEUTRAL, IMU_ACCEL_Z_NEUTRAL}
PRINT_CONFIG_MSG("Using single IMU accel neutral calibration")
#endif
#if defined(IMU_ACCEL_X_SENS) || defined(IMU_ACCEL_Y_SENS) || defined(IMU_ACCEL_Z_SENS)
#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}}
PRINT_CONFIG_MSG("Using single IMU accel sensitivity calibration")
#endif
#if defined(ACCEL_NEUTRAL) && defined(ACCEL_SCALE)
#define IMU_ACCEL_CALIB {{.abi_id=ABI_BROADCAST, .calibrated={.neutral=true, .scale=true}, .neutral=ACCEL_NEUTRAL, .scale=ACCEL_SCALE}}
#elif defined(ACCEL_NEUTRAL)
#define IMU_ACCEL_CALIB {{.abi_id=ABI_BROADCAST, .calibrated={.neutral=true}, .neutral=ACCEL_NEUTRAL}}
#elif defined(ACCEL_SCALE)
#define IMU_ACCEL_CALIB {{.abi_id=ABI_BROADCAST, .calibrated={.scale=true}, .scale=ACCEL_SCALE}}
#elif !defined(IMU_ACCEL_CALIB)
#define IMU_ACCEL_CALIB {}
#endif
/** By default mag signs are positive for single IMU with old format and defaults */
#if defined(IMU_MAG_CALIB) && (defined(IMU_MAG_X_SIGN) || defined(IMU_MAG_Y_SIGN) || defined(IMU_MAG_Z_SIGN))
#warning "The IMU_MAG_?_SIGN's aren't compatible with the IMU_MAG_CALIB define in the airframe"
#endif
#ifndef IMU_MAG_X_SIGN
#define IMU_MAG_X_SIGN 1
#endif
#ifndef IMU_MAG_Y_SIGN
#define IMU_MAG_Y_SIGN 1
#endif
#ifndef IMU_MAG_Z_SIGN
#define IMU_MAG_Z_SIGN 1
#endif
/** Default mag calibration is for single IMU with old format */
#if defined(IMU_MAG_X_NEUTRAL) || defined(IMU_MAG_Y_NEUTRAL) || defined(IMU_MAG_Z_NEUTRAL)
#define MAG_NEUTRAL {IMU_MAG_X_NEUTRAL, IMU_MAG_Y_NEUTRAL, IMU_MAG_Z_NEUTRAL}
PRINT_CONFIG_MSG("Using single IMU mag neutral calibration")
#endif
#if defined(IMU_MAG_X_SENS) || defined(IMU_MAG_Y_SENS) || defined(IMU_MAG_Z_SENS)
#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}}
PRINT_CONFIG_MSG("Using single IMU mag sensitivity calibration")
#endif
#if defined(MAG_NEUTRAL) && defined(MAG_SCALE)
#define IMU_MAG_CALIB {{.abi_id=ABI_BROADCAST, .calibrated={.neutral=true, .scale=true}, .neutral=MAG_NEUTRAL, .scale=MAG_SCALE}}
#elif defined(MAG_NEUTRAL)
#define IMU_MAG_CALIB {{.abi_id=ABI_BROADCAST, .calibrated={.neutral=true}, .neutral=MAG_NEUTRAL}}
#elif defined(MAG_SCALE)
#define IMU_MAG_CALIB {{.abi_id=ABI_BROADCAST, .calibrated={.scale=true}, .scale=MAG_SCALE}}
#elif !defined(IMU_MAG_CALIB)
#define IMU_MAG_CALIB {}
#endif
/** Default body to imu is 0 (radians) */
#if !defined(IMU_BODY_TO_IMU_PHI) && !defined(IMU_BODY_TO_IMU_THETA) && !defined(IMU_BODY_TO_IMU_PSI)
#define IMU_BODY_TO_IMU_PHI 0
#define IMU_BODY_TO_IMU_THETA 0
#define IMU_BODY_TO_IMU_PSI 0
#endif
PRINT_CONFIG_VAR(IMU_BODY_TO_IMU_PHI)
PRINT_CONFIG_VAR(IMU_BODY_TO_IMU_THETA)
PRINT_CONFIG_VAR(IMU_BODY_TO_IMU_PSI)
/** Which gyro measurements to send over telemetry/logging */
#ifndef IMU_GYRO_ABI_SEND_ID
#define IMU_GYRO_ABI_SEND_ID ABI_BROADCAST
#endif
PRINT_CONFIG_VAR(IMU_GYRO_ABI_SEND_ID)
/** Which accel measurements to send over telemetry/logging */
#ifndef IMU_ACCEL_ABI_SEND_ID
#define IMU_ACCEL_ABI_SEND_ID ABI_BROADCAST
#endif
PRINT_CONFIG_VAR(IMU_ACCEL_ABI_SEND_ID)
/** Which mag measurements to send over telemetry/logging */
#ifndef IMU_MAG_ABI_SEND_ID
#define IMU_MAG_ABI_SEND_ID ABI_BROADCAST
#endif
PRINT_CONFIG_VAR(IMU_MAG_ABI_SEND_ID)
/** By default log highspeed on the flightrecorder */
#ifndef IMU_LOG_HIGHSPEED_DEVICE
#define IMU_LOG_HIGHSPEED_DEVICE flightrecorder_sdlog
#endif
#if PERIODIC_TELEMETRY
#include "modules/datalink/telemetry.h"
static void send_accel_raw(struct transport_tx *trans, struct link_device *dev)
{
if(imu.accel_abi_send_id == ABI_DISABLE)
return;
static uint8_t id = 0;
pprz_msg_send_IMU_ACCEL_RAW(trans, dev, AC_ID, &imu.accels[id].abi_id, &imu.accels[id].temperature,
&imu.accels[id].unscaled.x, &imu.accels[id].unscaled.y, &imu.accels[id].unscaled.z);
if(imu.accel_abi_send_id != ABI_BROADCAST && imu.accels[id].abi_id == imu.accel_abi_send_id)
return;
id++;
if(id >= IMU_MAX_SENSORS || imu.accels[id].abi_id == ABI_DISABLE)
id = 0;
}
static void send_accel_scaled(struct transport_tx *trans, struct link_device *dev)
{
if(imu.accel_abi_send_id == ABI_DISABLE)
return;
static uint8_t id = 0;
pprz_msg_send_IMU_ACCEL_SCALED(trans, dev, AC_ID, &imu.accels[id].abi_id,
&imu.accels[id].scaled.x, &imu.accels[id].scaled.y, &imu.accels[id].scaled.z);
if(imu.accel_abi_send_id != ABI_BROADCAST && imu.accels[id].abi_id == imu.accel_abi_send_id)
return;
id++;
if(id >= IMU_MAX_SENSORS || imu.accels[id].abi_id == ABI_DISABLE)
id = 0;
}
static void send_accel(struct transport_tx *trans, struct link_device *dev)
{
if(imu.accel_abi_send_id == ABI_DISABLE)
return;
static uint8_t id = 0;
struct FloatVect3 accel_float;
ACCELS_FLOAT_OF_BFP(accel_float, imu.accels[id].scaled);
pprz_msg_send_IMU_ACCEL(trans, dev, AC_ID, &imu.accels[id].abi_id,
&accel_float.x, &accel_float.y, &accel_float.z);
if(imu.accel_abi_send_id != ABI_BROADCAST && imu.accels[id].abi_id == imu.accel_abi_send_id)
return;
id++;
if(id >= IMU_MAX_SENSORS || imu.accels[id].abi_id == ABI_DISABLE)
id = 0;
}
static void send_gyro_raw(struct transport_tx *trans, struct link_device *dev)
{
if(imu.gyro_abi_send_id == ABI_DISABLE)
return;
static uint8_t id = 0;
pprz_msg_send_IMU_GYRO_RAW(trans, dev, AC_ID, &imu.gyros[id].abi_id, &imu.gyros[id].temperature,
&imu.gyros[id].unscaled.p, &imu.gyros[id].unscaled.q, &imu.gyros[id].unscaled.r);
if(imu.gyro_abi_send_id != ABI_BROADCAST && imu.gyros[id].abi_id == imu.gyro_abi_send_id)
return;
id++;
if(id >= IMU_MAX_SENSORS || imu.gyros[id].abi_id == ABI_DISABLE)
id = 0;
}
static void send_gyro_scaled(struct transport_tx *trans, struct link_device *dev)
{
if(imu.gyro_abi_send_id == ABI_DISABLE)
return;
static uint8_t id = 0;
pprz_msg_send_IMU_GYRO_SCALED(trans, dev, AC_ID, &imu.gyros[id].abi_id,
&imu.gyros[id].scaled.p, &imu.gyros[id].scaled.q, &imu.gyros[id].scaled.r);
if(imu.gyro_abi_send_id != ABI_BROADCAST && imu.gyros[id].abi_id == imu.gyro_abi_send_id)
return;
id++;
if(id >= IMU_MAX_SENSORS || imu.gyros[id].abi_id == ABI_DISABLE)
id = 0;
}
static void send_gyro(struct transport_tx *trans, struct link_device *dev)
{
if(imu.gyro_abi_send_id == ABI_DISABLE)
return;
static uint8_t id = 0;
struct FloatRates gyro_float;
RATES_FLOAT_OF_BFP(gyro_float, imu.gyros[id].scaled);
pprz_msg_send_IMU_GYRO(trans, dev, AC_ID, &imu.gyros[id].abi_id,
&gyro_float.p, &gyro_float.q, &gyro_float.r);
if(imu.gyro_abi_send_id != ABI_BROADCAST && imu.gyros[id].abi_id == imu.gyro_abi_send_id)
return;
id++;
if(id >= IMU_MAX_SENSORS || imu.gyros[id].abi_id == ABI_DISABLE)
id = 0;
}
static void send_mag_raw(struct transport_tx *trans, struct link_device *dev)
{
if(imu.mag_abi_send_id == ABI_DISABLE)
return;
static uint8_t id = 0;
pprz_msg_send_IMU_MAG_RAW(trans, dev, AC_ID, &imu.mags[id].abi_id,
&imu.mags[id].unscaled.x, &imu.mags[id].unscaled.y, &imu.mags[id].unscaled.z);
if(imu.mag_abi_send_id != ABI_BROADCAST && imu.mags[id].abi_id == imu.mag_abi_send_id)
return;
id++;
if(id >= IMU_MAX_SENSORS || imu.mags[id].abi_id == ABI_DISABLE)
id = 0;
}
static void send_mag_scaled(struct transport_tx *trans, struct link_device *dev)
{
if(imu.mag_abi_send_id == ABI_DISABLE)
return;
static uint8_t id = 0;
pprz_msg_send_IMU_MAG_SCALED(trans, dev, AC_ID, &imu.mags[id].abi_id ,
&imu.mags[id].scaled.x, &imu.mags[id].scaled.y, &imu.mags[id].scaled.z);
if(imu.mag_abi_send_id != ABI_BROADCAST && imu.mags[id].abi_id == imu.mag_abi_send_id)
return;
id++;
if(id >= IMU_MAX_SENSORS || imu.mags[id].abi_id == ABI_DISABLE)
id = 0;
}
static void send_mag(struct transport_tx *trans, struct link_device *dev)
{
if(imu.mag_abi_send_id == ABI_DISABLE)
return;
static uint8_t id = 0;
struct FloatVect3 mag_float;
MAGS_FLOAT_OF_BFP(mag_float, imu.mags[id].scaled);
pprz_msg_send_IMU_MAG(trans, dev, AC_ID, &imu.mags[id].abi_id,
&mag_float.x, &mag_float.y, &mag_float.z);
if(imu.mag_abi_send_id != ABI_BROADCAST && imu.mags[id].abi_id == imu.mag_abi_send_id)
return;
id++;
if(id >= IMU_MAX_SENSORS || imu.mags[id].abi_id == ABI_DISABLE)
id = 0;
}
static void send_mag_current(struct transport_tx *trans, struct link_device *dev)
{
if(imu.mag_abi_send_id == ABI_DISABLE)
return;
static uint8_t id = 0;
pprz_msg_send_IMU_MAG_CURRENT_CALIBRATION(trans, dev, AC_ID,
&imu.mags[id].abi_id,
&imu.mags[id].unscaled.x,
&imu.mags[id].unscaled.y,
&imu.mags[id].unscaled.z,
&electrical.current);
if(imu.mag_abi_send_id != ABI_BROADCAST && imu.mags[id].abi_id == imu.mag_abi_send_id)
return;
id++;
if(id >= IMU_MAX_SENSORS || imu.mags[id].abi_id == ABI_DISABLE)
id = 0;
}
#endif /* PERIODIC_TELEMETRY */
struct Imu imu = {0};
static abi_event imu_gyro_raw_ev, imu_accel_raw_ev, imu_mag_raw_ev;
static void imu_gyro_raw_cb(uint8_t sender_id, uint32_t stamp, struct Int32Rates *data, uint8_t samples, float rate, float temp);
static void imu_accel_raw_cb(uint8_t sender_id, uint32_t stamp, struct Int32Vect3 *data, uint8_t samples, float rate, float temp);
static void imu_mag_raw_cb(uint8_t sender_id, uint32_t stamp, struct Int32Vect3 *data);
static void imu_set_body_to_imu_eulers(struct FloatEulers *body_to_imu_eulers);
void imu_init(void)
{
// Set the Body to IMU rotation
struct FloatEulers body_to_imu_eulers = {IMU_BODY_TO_IMU_PHI, IMU_BODY_TO_IMU_THETA, IMU_BODY_TO_IMU_PSI};
orientationSetEulers_f(&imu.body_to_imu, &body_to_imu_eulers);
struct Int32RMat *body_to_imu_rmat = orientationGetRMat_i(&imu.body_to_imu);
// Set the calibrated sensors
struct Int32RMat body_to_sensor;
const struct imu_gyro_t gyro_calib[] = IMU_GYRO_CALIB;
const struct imu_accel_t accel_calib[] = IMU_ACCEL_CALIB;
const struct imu_mag_t mag_calib[] = IMU_MAG_CALIB;
const uint8_t gyro_calib_len = sizeof(gyro_calib) / sizeof(struct imu_gyro_t);
const uint8_t accel_calib_len = sizeof(accel_calib) / sizeof(struct imu_accel_t);
const uint8_t mag_calib_len = sizeof(mag_calib) / sizeof(struct imu_mag_t);
// Initialize the sensors to default values
for(uint8_t i = 0; i < IMU_MAX_SENSORS; i++) {
/* Copy gyro calibration if needed */
if(i >= gyro_calib_len) {
imu.gyros[i].abi_id = ABI_DISABLE;
imu.gyros[i].calibrated.neutral = false;
imu.gyros[i].calibrated.scale = false;
imu.gyros[i].calibrated.rotation = false;
imu.gyros[i].calibrated.filter = false;
} else {
imu.gyros[i] = gyro_calib[i];
}
// Set the default safe values if not calibrated
if(!imu.gyros[i].calibrated.neutral) {
INT_RATES_ZERO(imu.gyros[i].neutral);
}
if(!imu.gyros[i].calibrated.scale) {
RATES_ASSIGN(imu.gyros[i].scale[0], IMU_GYRO_P_SIGN, IMU_GYRO_Q_SIGN, IMU_GYRO_R_SIGN);
RATES_ASSIGN(imu.gyros[i].scale[1], 1, 1, 1);
}
if(!imu.gyros[i].calibrated.rotation) {
int32_rmat_identity(&imu.gyros[i].body_to_sensor);
}
imu.gyros[i].last_stamp = 0;
int32_rmat_comp(&body_to_sensor, body_to_imu_rmat, &imu.gyros[i].body_to_sensor);
RMAT_COPY(imu.gyros[i].body_to_sensor, body_to_sensor);
if(imu.gyros[i].calibrated.filter) {
float tau = 1.0 / (2.0 * M_PI * imu.gyros[i].filter_freq);
float sample_time = 1 / imu.gyros[i].filter_sample_freq;
for(uint8_t j = 0; j < 3; j++)
init_butterworth_2_low_pass(&imu.gyros[i].filter[j], tau, sample_time, 0.0);
}
/* Copy accel calibration if needed */
if(i >= accel_calib_len) {
imu.accels[i].abi_id = ABI_DISABLE;
imu.accels[i].calibrated.neutral = false;
imu.accels[i].calibrated.scale = false;
imu.accels[i].calibrated.rotation = false;
imu.accels[i].calibrated.filter = false;
} else {
imu.accels[i] = accel_calib[i];
}
// Set the default safe values if not calibrated
if(!imu.accels[i].calibrated.neutral) {
INT_VECT3_ZERO(imu.accels[i].neutral);
}
if(!imu.accels[i].calibrated.scale) {
VECT3_ASSIGN(imu.accels[i].scale[0], IMU_ACCEL_X_SIGN, IMU_ACCEL_Y_SIGN, IMU_ACCEL_Z_SIGN);
VECT3_ASSIGN(imu.accels[i].scale[1], 1, 1, 1);
}
if(!imu.accels[i].calibrated.rotation) {
int32_rmat_identity(&imu.accels[i].body_to_sensor);
}
imu.accels[i].last_stamp = 0;
int32_rmat_comp(&body_to_sensor, body_to_imu_rmat, &imu.accels[i].body_to_sensor);
RMAT_COPY(imu.accels[i].body_to_sensor, body_to_sensor);
if(imu.accels[i].calibrated.filter) {
float tau = 1.0 / (2.0 * M_PI * imu.accels[i].filter_freq);
float sample_time = 1 / imu.accels[i].filter_sample_freq;
for(uint8_t j = 0; j < 3; j++)
init_butterworth_2_low_pass(&imu.accels[i].filter[j], tau, sample_time, 0.0);
}
/* Copy mag calibrated if needed */
if(i >= mag_calib_len) {
imu.mags[i].abi_id = ABI_DISABLE;
imu.mags[i].calibrated.neutral = false;
imu.mags[i].calibrated.scale = false;
imu.mags[i].calibrated.rotation = false;
imu.mags[i].calibrated.current = false;
} else {
imu.mags[i] = mag_calib[i];
}
// Set the default safe values if not calibrated
if(!imu.mags[i].calibrated.neutral) {
INT_VECT3_ZERO(imu.mags[i].neutral);
}
if(!imu.mags[i].calibrated.scale) {
VECT3_ASSIGN(imu.mags[i].scale[0], IMU_MAG_X_SIGN, IMU_MAG_Y_SIGN, IMU_MAG_Z_SIGN);
VECT3_ASSIGN(imu.mags[i].scale[1], 1, 1, 1);
}
if(!imu.mags[i].calibrated.rotation) {
int32_rmat_identity(&imu.mags[i].body_to_sensor);
}
if(!imu.mags[i].calibrated.current) {
INT_VECT3_ZERO(imu.mags[i].current_scale);
}
int32_rmat_comp(&body_to_sensor, body_to_imu_rmat, &imu.mags[i].body_to_sensor);
RMAT_COPY(imu.mags[i].body_to_sensor, body_to_sensor);
}
// Bind to raw measurements
AbiBindMsgIMU_GYRO_RAW(ABI_BROADCAST, &imu_gyro_raw_ev, imu_gyro_raw_cb);
AbiBindMsgIMU_ACCEL_RAW(ABI_BROADCAST, &imu_accel_raw_ev, imu_accel_raw_cb);
AbiBindMsgIMU_MAG_RAW(ABI_BROADCAST, &imu_mag_raw_ev, imu_mag_raw_cb);
#if PERIODIC_TELEMETRY
register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_IMU_ACCEL_RAW, send_accel_raw);
register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_IMU_ACCEL_SCALED, send_accel_scaled);
register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_IMU_ACCEL, send_accel);
register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_IMU_GYRO_RAW, send_gyro_raw);
register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_IMU_GYRO_SCALED, send_gyro_scaled);
register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_IMU_GYRO, send_gyro);
register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_IMU_MAG_RAW, send_mag_raw);
register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_IMU_MAG_SCALED, send_mag_scaled);
register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_IMU_MAG, send_mag);
register_periodic_telemetry(DefaultPeriodic, PPRZ_MSG_ID_IMU_MAG_CURRENT_CALIBRATION, send_mag_current);
#endif // DOWNLINK
// Set defaults
imu.gyro_abi_send_id = IMU_GYRO_ABI_SEND_ID;
imu.accel_abi_send_id = IMU_ACCEL_ABI_SEND_ID;
imu.mag_abi_send_id = IMU_MAG_ABI_SEND_ID;
imu.initialized = true;
}
/**
* @brief Set the defaults for a gyro sensor
* WARNING: Should be called before sensor is publishing messages to ensure correct values
* @param abi_id The ABI sender id to set the defaults for
* @param imu_to_sensor Imu to sensor rotation matrix
* @param neutral Neutral values
* @param scale Scale values, 0 index is multiply and 1 index is divide
*/
void imu_set_defaults_gyro(uint8_t abi_id, const struct Int32RMat *imu_to_sensor, const struct Int32Rates *neutral, const struct Int32Rates *scale)
{
// Find the correct gyro
struct imu_gyro_t *gyro = imu_get_gyro(abi_id, true);
if(gyro == NULL)
return;
// Copy the defaults
if(imu_to_sensor != NULL && !gyro->calibrated.rotation) {
struct Int32RMat body_to_sensor;
struct Int32RMat *body_to_imu = orientationGetRMat_i(&imu.body_to_imu);
int32_rmat_comp(&body_to_sensor, body_to_imu, imu_to_sensor);
RMAT_COPY(gyro->body_to_sensor, body_to_sensor);
}
if(neutral != NULL && !gyro->calibrated.neutral)
RATES_COPY(gyro->neutral, *neutral);
if(scale != NULL && !gyro->calibrated.scale) {
RATES_ASSIGN(gyro->scale[0], IMU_GYRO_P_SIGN*scale[0].p, IMU_GYRO_Q_SIGN*scale[0].q, IMU_GYRO_R_SIGN*scale[0].r);
RATES_COPY(gyro->scale[1], scale[1]);
}
}
/**
* @brief Set the defaults for a accel sensor
* WARNING: Should be called before sensor is publishing messages to ensure correct values
* @param abi_id The ABI sender id to set the defaults for
* @param imu_to_sensor Imu to sensor rotation matrix
* @param neutral Neutral values
* @param scale Scale values, 0 index is multiply and 1 index is divide
*/
void imu_set_defaults_accel(uint8_t abi_id, const struct Int32RMat *imu_to_sensor, const struct Int32Vect3 *neutral, const struct Int32Vect3 *scale)
{
// Find the correct accel
struct imu_accel_t *accel = imu_get_accel(abi_id, true);
if(accel == NULL)
return;
// Copy the defaults
if(imu_to_sensor != NULL && !accel->calibrated.rotation) {
struct Int32RMat body_to_sensor;
struct Int32RMat *body_to_imu = orientationGetRMat_i(&imu.body_to_imu);
int32_rmat_comp(&body_to_sensor, body_to_imu, imu_to_sensor);
RMAT_COPY(accel->body_to_sensor, body_to_sensor);
}
if(neutral != NULL && !accel->calibrated.neutral)
VECT3_COPY(accel->neutral, *neutral);
if(scale != NULL && !accel->calibrated.scale) {
VECT3_ASSIGN(accel->scale[0], IMU_ACCEL_X_SIGN*scale[0].x, IMU_ACCEL_Y_SIGN*scale[0].y, IMU_ACCEL_Z_SIGN*scale[0].z);
VECT3_COPY(accel->scale[1], scale[1]);
}
}
/**
* @brief Set the defaults for a mag sensor
* WARNING: Should be called before sensor is publishing messages to ensure correct values
* @param abi_id The ABI sender id to set the defaults for
* @param imu_to_sensor Imu to sensor rotation matrix
* @param neutral Neutral values
* @param scale Scale values, 0 index is multiply and 1 index is divide
*/
void imu_set_defaults_mag(uint8_t abi_id, const struct Int32RMat *imu_to_sensor, const struct Int32Vect3 *neutral, const struct Int32Vect3 *scale)
{
// Find the correct mag
struct imu_mag_t *mag = imu_get_mag(abi_id, true);
if(mag == NULL)
return;
// Copy the defaults
if(imu_to_sensor != NULL && !mag->calibrated.rotation) {
struct Int32RMat body_to_sensor;
struct Int32RMat *body_to_imu = orientationGetRMat_i(&imu.body_to_imu);
int32_rmat_comp(&body_to_sensor, body_to_imu, imu_to_sensor);
RMAT_COPY(mag->body_to_sensor, body_to_sensor);
}
if(neutral != NULL && !mag->calibrated.neutral)
VECT3_COPY(mag->neutral, *neutral);
if(scale != NULL && !mag->calibrated.scale) {
VECT3_ASSIGN(mag->scale[0], IMU_MAG_X_SIGN*scale[0].x, IMU_MAG_Y_SIGN*scale[0].y, IMU_MAG_Z_SIGN*scale[0].z);
VECT3_COPY(mag->scale[1], scale[1]);
}
}
static void imu_gyro_raw_cb(uint8_t sender_id, uint32_t stamp, struct Int32Rates *data, uint8_t samples, float rate, float temp)
{
// Find the correct gyro
struct imu_gyro_t *gyro = imu_get_gyro(sender_id, true);
if(gyro == NULL || samples < 1)
return;
// Filter the gyro
struct Int32Rates data_filtered[samples];
if(gyro->calibrated.filter) {
for(uint8_t i = 0; i < samples; i++) {
data_filtered[i].p = update_butterworth_2_low_pass(&gyro->filter[0], data[i].p);
data_filtered[i].q = update_butterworth_2_low_pass(&gyro->filter[1], data[i].q);
data_filtered[i].r = update_butterworth_2_low_pass(&gyro->filter[2], data[i].r);
}
data = data_filtered;
}
// Copy last sample as unscaled
RATES_COPY(gyro->unscaled, data[samples-1]);
// Scale the gyro
struct Int32Rates scaled, scaled_rot;
scaled.p = (gyro->unscaled.p - gyro->neutral.p) * gyro->scale[0].p / gyro->scale[1].p;
scaled.q = (gyro->unscaled.q - gyro->neutral.q) * gyro->scale[0].q / gyro->scale[1].q;
scaled.r = (gyro->unscaled.r - gyro->neutral.r) * gyro->scale[0].r / gyro->scale[1].r;
// Rotate the sensor
int32_rmat_transp_ratemult(&scaled_rot, &gyro->body_to_sensor, &scaled);
#if IMU_INTEGRATION
// Only integrate if we have gotten a previous measurement and didn't overflow the timer
if(!isnan(rate) && gyro->last_stamp > 0 && stamp > gyro->last_stamp) {
struct FloatRates integrated;
// Trapezoidal integration (TODO: coning correction)
integrated.p = RATE_FLOAT_OF_BFP(gyro->scaled.p + scaled_rot.p) * 0.5f;
integrated.q = RATE_FLOAT_OF_BFP(gyro->scaled.q + scaled_rot.q) * 0.5f;
integrated.r = RATE_FLOAT_OF_BFP(gyro->scaled.r + scaled_rot.r) * 0.5f;
// Only perform multiple integrations in sensor frame if needed
if(samples > 1) {
struct FloatRates integrated_sensor;
struct FloatRMat body_to_sensor;
// Rotate back to sensor frame
RMAT_FLOAT_OF_BFP(body_to_sensor, gyro->body_to_sensor);
float_rmat_ratemult(&integrated_sensor, &body_to_sensor, &integrated);
// Add all the other samples
for(uint8_t i = 0; i < samples-1; i++) {
struct FloatRates f_sample;
f_sample.p = RATE_FLOAT_OF_BFP((data[i].p - gyro->neutral.p) * gyro->scale[0].p / gyro->scale[1].p);
f_sample.q = RATE_FLOAT_OF_BFP((data[i].q - gyro->neutral.q) * gyro->scale[0].q / gyro->scale[1].q);
f_sample.r = RATE_FLOAT_OF_BFP((data[i].r - gyro->neutral.r) * gyro->scale[0].r / gyro->scale[1].r);
#if IMU_LOG_HIGHSPEED
pprz_msg_send_IMU_GYRO(&pprzlog_tp.trans_tx, &(IMU_LOG_HIGHSPEED_DEVICE).device, AC_ID, &sender_id, &f_sample.p, &f_sample.q, &f_sample.r);
#endif
integrated_sensor.p += f_sample.p;
integrated_sensor.q += f_sample.q;
integrated_sensor.r += f_sample.r;
}
// Rotate to body frame
float_rmat_transp_ratemult(&integrated, &body_to_sensor, &integrated_sensor);
}
// Divide by the time of the collected samples
integrated.p = integrated.p * (1.f / rate);
integrated.q = integrated.q * (1.f / rate);
integrated.r = integrated.r * (1.f / rate);
// Send the integrated values
uint16_t dt = (1e6 / rate) * samples;
AbiSendMsgIMU_GYRO_INT(sender_id, stamp, &integrated, dt);
}
#else
(void)rate; // Surpress compile warning not used
#endif
#if IMU_LOG_HIGHSPEED
struct FloatRates f_sample;
RATES_FLOAT_OF_BFP(f_sample, scaled);
pprz_msg_send_IMU_GYRO(&pprzlog_tp.trans_tx, &(IMU_LOG_HIGHSPEED_DEVICE).device, AC_ID, &sender_id, &f_sample.p, &f_sample.q, &f_sample.r);
#endif
// Copy and send
gyro->temperature = temp;
RATES_COPY(gyro->scaled, scaled_rot);
AbiSendMsgIMU_GYRO(sender_id, stamp, &gyro->scaled);
gyro->last_stamp = stamp;
}
static void imu_accel_raw_cb(uint8_t sender_id, uint32_t stamp, struct Int32Vect3 *data, uint8_t samples, float rate, float temp)
{
// Find the correct accel
struct imu_accel_t *accel = imu_get_accel(sender_id, true);
if(accel == NULL || samples < 1)
return;
// Filter the accel
struct Int32Vect3 data_filtered[samples];
if(accel->calibrated.filter) {
for(uint8_t i = 0; i < samples; i++) {
data_filtered[i].x = update_butterworth_2_low_pass(&accel->filter[0], data[i].x);
data_filtered[i].y = update_butterworth_2_low_pass(&accel->filter[1], data[i].y);
data_filtered[i].z = update_butterworth_2_low_pass(&accel->filter[2], data[i].z);
}
data = data_filtered;
}
// Copy last sample as unscaled
VECT3_COPY(accel->unscaled, data[samples-1]);
// Scale the accel
struct Int32Vect3 scaled, scaled_rot;
scaled.x = (accel->unscaled.x - accel->neutral.x) * accel->scale[0].x / accel->scale[1].x;
scaled.y = (accel->unscaled.y - accel->neutral.y) * accel->scale[0].y / accel->scale[1].y;
scaled.z = (accel->unscaled.z - accel->neutral.z) * accel->scale[0].z / accel->scale[1].z;
// Rotate the sensor
int32_rmat_transp_vmult(&scaled_rot, &accel->body_to_sensor, &scaled);
#if IMU_INTEGRATION
// Only integrate if we have gotten a previous measurement and didn't overflow the timer
if(!isnan(rate) && accel->last_stamp > 0 && stamp > accel->last_stamp) {
struct FloatVect3 integrated;
// Trapezoidal integration
integrated.x = ACCEL_FLOAT_OF_BFP(accel->scaled.x + scaled_rot.x) * 0.5f;
integrated.y = ACCEL_FLOAT_OF_BFP(accel->scaled.y + scaled_rot.y) * 0.5f;
integrated.z = ACCEL_FLOAT_OF_BFP(accel->scaled.z + scaled_rot.z) * 0.5f;
// Only perform multiple integrations in sensor frame if needed
if(samples > 1) {
struct FloatVect3 integrated_sensor;
struct FloatRMat body_to_sensor;
// Rotate back to sensor frame
RMAT_FLOAT_OF_BFP(body_to_sensor, accel->body_to_sensor);
float_rmat_vmult(&integrated_sensor, &body_to_sensor, &integrated);
// Add all the other samples
for(uint8_t i = 0; i < samples-1; i++) {
struct FloatVect3 f_sample;
f_sample.x = ACCEL_FLOAT_OF_BFP((data[i].x - accel->neutral.x) * accel->scale[0].x / accel->scale[1].x);
f_sample.y = ACCEL_FLOAT_OF_BFP((data[i].y - accel->neutral.y) * accel->scale[0].y / accel->scale[1].y);
f_sample.z = ACCEL_FLOAT_OF_BFP((data[i].z - accel->neutral.z) * accel->scale[0].z / accel->scale[1].z);
#if IMU_LOG_HIGHSPEED
pprz_msg_send_IMU_ACCEL(&pprzlog_tp.trans_tx, &(IMU_LOG_HIGHSPEED_DEVICE).device, AC_ID, &sender_id, &f_sample.x, &f_sample.y, &f_sample.z);
#endif
integrated_sensor.x += f_sample.x;
integrated_sensor.y += f_sample.y;
integrated_sensor.z += f_sample.z;
}
// Rotate to body frame
float_rmat_transp_vmult(&integrated, &body_to_sensor, &integrated_sensor);
}
// Divide by the time of the collected samples
integrated.x = integrated.x * (1.f / rate);
integrated.y = integrated.y * (1.f / rate);
integrated.z = integrated.z * (1.f / rate);
// Send the integrated values
uint16_t dt = (1e6 / rate) * samples;
AbiSendMsgIMU_ACCEL_INT(sender_id, stamp, &integrated, dt);
}
#else
(void)rate; // Surpress compile warning not used
#endif
#if IMU_LOG_HIGHSPEED
struct FloatVect3 f_sample;
ACCELS_FLOAT_OF_BFP(f_sample, scaled);
pprz_msg_send_IMU_ACCEL(&pprzlog_tp.trans_tx, &(IMU_LOG_HIGHSPEED_DEVICE).device, AC_ID, &sender_id, &f_sample.x, &f_sample.y, &f_sample.z);
#endif
// Copy and send
accel->temperature = temp;
VECT3_COPY(accel->scaled, scaled_rot);
AbiSendMsgIMU_ACCEL(sender_id, stamp, &accel->scaled);
accel->last_stamp = stamp;
}
static void imu_mag_raw_cb(uint8_t sender_id, uint32_t stamp, struct Int32Vect3 *data)
{
// Find the correct mag
struct imu_mag_t *mag = imu_get_mag(sender_id, true);
if(mag == NULL)
return;
// Calculate current compensation
struct Int32Vect3 mag_correction;
mag_correction.x = (int32_t)(mag->current_scale.x * (float) electrical.current);
mag_correction.y = (int32_t)(mag->current_scale.y * (float) electrical.current);
mag_correction.z = (int32_t)(mag->current_scale.z * (float) electrical.current);
// Copy last sample as unscaled
VECT3_COPY(mag->unscaled, *data);
// Scale the mag
struct Int32Vect3 scaled;
scaled.x = (mag->unscaled.x - mag_correction.x - mag->neutral.x) * mag->scale[0].x / mag->scale[1].x;
scaled.y = (mag->unscaled.y - mag_correction.y - mag->neutral.y) * mag->scale[0].y / mag->scale[1].y;
scaled.z = (mag->unscaled.z - mag_correction.z - mag->neutral.z) * mag->scale[0].z / mag->scale[1].z;
// Rotate the sensor
int32_rmat_transp_vmult(&mag->scaled, &mag->body_to_sensor, &scaled);
AbiSendMsgIMU_MAG(sender_id, stamp, &mag->scaled);
}
/**
* @brief Find or create the gyro in the imu structure
*
* @param sender_id The ABI sender id to search for
* @param create Create a new index if not found
* @return struct imu_gyro_t* The gyro structure if found/created else NULL
*/
struct imu_gyro_t *imu_get_gyro(uint8_t sender_id, bool create) {
// Find the correct gyro or create index
// If abi_id was set to broadcast (assuming a single IMU case), the first request takes the index for himself
struct imu_gyro_t *gyro = NULL;
for(uint8_t i = 0; i < IMU_MAX_SENSORS; i++) {
if(imu.gyros[i].abi_id == sender_id || (create && (imu.gyros[i].abi_id == ABI_BROADCAST || imu.gyros[i].abi_id == ABI_DISABLE))) {
gyro = &imu.gyros[i];
gyro->abi_id = sender_id;
break;
} else if(sender_id == ABI_BROADCAST && imu.gyros[i].abi_id != ABI_DISABLE) {
gyro = &imu.gyros[i];
}
}
return gyro;
}
/**
* @brief Find or create the accel in the imu structure
*
* @param sender_id The ABI sender id to search for
* @param create Create a new index if not found
* @return struct imu_accel_t* The accel structure if found/created else NULL
*/
struct imu_accel_t *imu_get_accel(uint8_t sender_id, bool create) {
// Find the correct accel
// If abi_id was set to broadcast (assuming a single IMU case), the first request takes the index for himself
struct imu_accel_t *accel = NULL;
for(uint8_t i = 0; i < IMU_MAX_SENSORS; i++) {
if(imu.accels[i].abi_id == sender_id || (create && (imu.accels[i].abi_id == ABI_BROADCAST || imu.accels[i].abi_id == ABI_DISABLE))) {
accel = &imu.accels[i];
accel->abi_id = sender_id;
break;
} else if(sender_id == ABI_BROADCAST && imu.accels[i].abi_id != ABI_DISABLE) {
accel = &imu.accels[i];
}
}
return accel;
}
/**
* @brief Find or create the mag in the imu structure
*
* @param sender_id The ABI sender id to search for
* @param create Create a new index if not found
* @return struct imu_mag_t* The mag structure if found/created else NULL
*/
struct imu_mag_t *imu_get_mag(uint8_t sender_id, bool create) {
// Find the correct mag
// If abi_id was set to broadcast (assuming a single IMU case), the first request takes the index for himself
struct imu_mag_t *mag = NULL;
for(uint8_t i = 0; i < IMU_MAX_SENSORS; i++) {
if(imu.mags[i].abi_id == sender_id || (create && (imu.mags[i].abi_id == ABI_BROADCAST || imu.mags[i].abi_id == ABI_DISABLE))) {
mag = &imu.mags[i];
mag->abi_id = sender_id;
break;
} else if(sender_id == ABI_BROADCAST && imu.mags[i].abi_id != ABI_DISABLE) {
mag = &imu.mags[i];
}
}
return mag;
}
/**
* @brief Set the body to IMU rotation in eulers
* This will update all the sensor values
* @param body_to_imu_eulers 321 Euler angles in radians
*/
static void imu_set_body_to_imu_eulers(struct FloatEulers *body_to_imu_eulers)
{
struct Int32RMat new_body_to_imu, diff_body_to_imu;
struct Int32Eulers body_to_imu_eulers_i;
// Convert to RMat
struct Int32RMat *old_body_to_imu = orientationGetRMat_i(&imu.body_to_imu);
EULERS_BFP_OF_REAL(body_to_imu_eulers_i, *body_to_imu_eulers);
int32_rmat_of_eulers(&new_body_to_imu, &body_to_imu_eulers_i);
// Calculate the difference between old and new
int32_rmat_comp_inv(&diff_body_to_imu, &new_body_to_imu, old_body_to_imu);
// Apply the difference to all sensors
struct Int32RMat old_rmat;
for(uint8_t i = 0; i < IMU_MAX_SENSORS; i++) {
old_rmat = imu.gyros[i].body_to_sensor;
int32_rmat_comp(&imu.gyros[i].body_to_sensor, &diff_body_to_imu, &old_rmat);
old_rmat = imu.accels[i].body_to_sensor;
int32_rmat_comp(&imu.accels[i].body_to_sensor, &diff_body_to_imu, &old_rmat);
old_rmat = imu.mags[i].body_to_sensor;
int32_rmat_comp(&imu.mags[i].body_to_sensor, &diff_body_to_imu, &old_rmat);
}
// Set the current body to imu
orientationSetEulers_f(&imu.body_to_imu, body_to_imu_eulers);
}
void imu_SetBodyToImuPhi(float phi)
{
struct FloatEulers body_to_imu_eulers;
body_to_imu_eulers = *orientationGetEulers_f(&imu.body_to_imu);
body_to_imu_eulers.phi = phi;
imu_set_body_to_imu_eulers(&body_to_imu_eulers);
}
void imu_SetBodyToImuTheta(float theta)
{
struct FloatEulers body_to_imu_eulers;
body_to_imu_eulers = *orientationGetEulers_f(&imu.body_to_imu);
body_to_imu_eulers.theta = theta;
imu_set_body_to_imu_eulers(&body_to_imu_eulers);
}
void imu_SetBodyToImuPsi(float psi)
{
struct FloatEulers body_to_imu_eulers;
body_to_imu_eulers = *orientationGetEulers_f(&imu.body_to_imu);
body_to_imu_eulers.psi = psi;
imu_set_body_to_imu_eulers(&body_to_imu_eulers);
}
void imu_SetBodyToImuCurrent(float set)
{
imu.b2i_set_current = set;
if (imu.b2i_set_current) {
// adjust imu_to_body roll and pitch by current NedToBody roll and pitch
struct FloatEulers body_to_imu_eulers;
body_to_imu_eulers = *orientationGetEulers_f(&imu.body_to_imu);
if (stateIsAttitudeValid()) {
// adjust imu_to_body roll and pitch by current NedToBody roll and pitch
body_to_imu_eulers.phi += stateGetNedToBodyEulers_f()->phi;
body_to_imu_eulers.theta += stateGetNedToBodyEulers_f()->theta;
imu_set_body_to_imu_eulers(&body_to_imu_eulers);
} else {
// indicate that we couldn't set to current roll/pitch
imu.b2i_set_current = false;
}
} else {
// reset to BODY_TO_IMU as defined in airframe file
struct FloatEulers body_to_imu_eulers = {IMU_BODY_TO_IMU_PHI, IMU_BODY_TO_IMU_THETA, IMU_BODY_TO_IMU_PSI};
imu_set_body_to_imu_eulers(&body_to_imu_eulers);
}
}