-
Notifications
You must be signed in to change notification settings - Fork 33
/
Copy pathNineAxesMotion.cpp
executable file
·1226 lines (1138 loc) · 42.6 KB
/
NineAxesMotion.cpp
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
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/****************************************************************************
* Copyright (C) 2011 - 2014 Bosch Sensortec GmbH
*
* NineAxesMotion.cpp
* Date: 2015/02/10
* Revision: 3.0 $
*
* Usage: Source file of the C++ Wrapper for the BNO055 Sensor API
*
****************************************************************************
*
* Added Arduino M0/M0 Pro support
*
* Date: 07/27/2015
*
* Modified by: Arduino.org development Team.
*
****************************************************************************
/***************************************************************************
* License:
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* Neither the name of the copyright holder nor the names of the
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE
*
* The information provided is believed to be accurate and reliable.
* The copyright holder assumes no responsibility for the consequences of use
* of such information nor for any infringement of patents or
* other rights of third parties which may result from its use.
* No license is granted by implication or otherwise under any patent or
* patent rights of the copyright holder.
*/
#include "NineAxesMotion.h"
//Function Definitions
/*******************************************************************************************
*Description: Constructor of the class with the default initialization
*Input Parameters: None
*Return Parameter: None
*******************************************************************************************/
NineAxesMotion::NineAxesMotion()
{
//Blank
}
/*******************************************************************************************
*Description: Function with the bare minimum initialization
*Input Parameters: None
*Return Parameter: None
*******************************************************************************************/
void NineAxesMotion::initSensor(unsigned int address)
{
//Initialize the GPIO peripheral
pinMode(INT_PIN, INPUT_PULLUP); //Configure Interrupt pin
pinMode(RESET_PIN, OUTPUT); //Configure Reset pin
//Power on the BNO055
resetSensor(address);
}
/*******************************************************************************************
*Description: This function is used to reset the BNO055
*Input Parameters: None
*Return Parameter: None
*******************************************************************************************/
void NineAxesMotion::resetSensor(unsigned int address)
{
//Reset sequence
digitalWrite(RESET_PIN, LOW); //Set the Reset pin LOW
delay(RESET_PERIOD); //Hold it for a while
digitalWrite(RESET_PIN, HIGH); //Set the Reset pin HIGH
delay(INIT_PERIOD); //Pause for a while to let the sensor initialize completely (Anything >500ms should be fine)
//Initialization sequence
//Link the function pointers for communication (late-binding)
myBNO.bus_read = BNO055_I2C_bus_read;
myBNO.bus_write = BNO055_I2C_bus_write;
myBNO.delay_msec = _delay;
//Set the I2C address here !!! ADDR1 is the default address
//myBNO.dev_addr = BNO055_I2C_ADDR1;
myBNO.dev_addr = address;
//myBNO.dev_addr = BNO055_I2C_ADDR2;
//Initialize the BNO055 structure to hold the device information
bno055_init(&myBNO);
//Post initialization delay
delay(POST_INIT_PERIOD);
//To set the output data format to the Android style
bno055_set_data_output_format(ANDROID);
//Set the default data update mode to auto
dataUpdateMode = AUTO;
}
/*******************************************************************************************
*Description: This function is used to set the operation mode of the BNO055
*Input Parameters:
* byte operationMode: To assign which operation mode the device has to
* ---------------------------------------------------
* Constant Definition Constant Value Comment
* ---------------------------------------------------
* OPERATION_MODE_CONFIG 0x00 Configuration Mode
* (Transient Mode)
* OPERATION_MODE_ACCONLY 0x01 Accelerometer only
* OPERATION_MODE_MAGONLY 0x02 Magnetometer only
* OPERATION_MODE_GYRONLY 0x03 Gyroscope only
* OPERATION_MODE_ACCMAG 0x04 Accelerometer and Magnetometer only
* OPERATION_MODE_ACCGYRO 0x05 Accelerometer and Gyroscope only
* OPERATION_MODE_MAGGYRO 0x06 Magnetometer and Gyroscope only
* OPERATION_MODE_AMG 0x07 Accelerometer, Magnetometer and
* Gyroscope (without fusion)
* OPERATION_MODE_IMUPLUS 0x08 Inertial Measurement Unit
* (Accelerometer and Gyroscope
* Sensor Fusion Mode)
* OPERATION_MODE_COMPASS 0x09 Tilt Compensated Compass
* (Accelerometer and Magnetometer
* Sensor Fusion Mode)
* OPERATION_MODE_M4G 0x0A Magnetometer and Gyroscope Sensor
* Fusion Mode
* OPERATION_MODE_NDOF_FMC_OFF 0x0B 9 Degrees of Freedom Sensor Fusion
* with Fast Magnetometer Calibration Off
* OPERATION_MODE_NDOF 0x0C 9 Degrees of Freedom Sensor Fusion
*Return Parameter: None
*******************************************************************************************/
void NineAxesMotion::setOperationMode(byte operationMode)
{
BNO055_RETURN_FUNCTION_TYPE comRes = BNO055_ZERO_U8X; //Holds the communication results
comRes = bno055_set_operation_mode(operationMode); //Set the Operation Mode
}
/*******************************************************************************************
*Description: This function is used to set the power mode
*Input Parameters:
* byte powerMode: To assign the power mode the device has to switch to
* --------------------------------------
* Constant Definition Constant Value
* --------------------------------------
* POWER_MODE_NORMAL 0x00
* POWER_MODE_LOWPOWER 0x01
* POWER_MODE_SUSPEND 0x02
*Return Parameter:
*******************************************************************************************/
void NineAxesMotion::setPowerMode(byte powerMode)
{
BNO055_RETURN_FUNCTION_TYPE comRes = BNO055_ZERO_U8X; //Holds the communication results
comRes = bno055_set_power_mode(powerMode); //Set the Power Mode
}
/*******************************************************************************************
*Description: This function is used to update the accelerometer data in m/s2
*Input Parameters: None
*Return Parameter: None
*******************************************************************************************/
void NineAxesMotion::updateAccel(void)
{
BNO055_RETURN_FUNCTION_TYPE comRes = BNO055_ZERO_U8X; //Holds the communication results
comRes = bno055_convert_float_accel_xyz_msq(&accelData); //Read the data from the sensor
}
/*******************************************************************************************
*Description: This function is used to update the magnetometer data in microTesla
*Input Parameters: None
*Return Parameter: None
*******************************************************************************************/
void NineAxesMotion::updateMag(void)
{
BNO055_RETURN_FUNCTION_TYPE comRes = BNO055_ZERO_U8X; //Holds the communication results
comRes = bno055_convert_float_mag_xyz_uT(&magData); //Read the data from the sensor
}
/*******************************************************************************************
*Description: This function is used to update the gyroscope data in deg/s
*Input Parameters: None
*Return Parameter: None
*******************************************************************************************/
void NineAxesMotion::updateGyro(void)
{
BNO055_RETURN_FUNCTION_TYPE comRes = BNO055_ZERO_U8X; //Holds the communication results
comRes = bno055_convert_float_gyro_xyz_dps(&gyroData); //Read the data from the sensor
}
/*******************************************************************************************
*Description: This function is used to update the quaternion data
*Input Parameters: None
*Return Parameter: None
*******************************************************************************************/
void NineAxesMotion::updateQuat(void)
{
BNO055_RETURN_FUNCTION_TYPE comRes = BNO055_ZERO_U8X; //Holds the communication results
comRes = bno055_read_quaternion_wxyz(&quatData); //Read the data from the sensor
}
/*******************************************************************************************
*Description: This function is used to update the euler data in degrees
*Input Parameters: None
*Return Parameter: None
*******************************************************************************************/
void NineAxesMotion::updateEuler(void)
{
BNO055_RETURN_FUNCTION_TYPE comRes = BNO055_ZERO_U8X; //Holds the communication results
comRes = bno055_convert_float_euler_hpr_deg(&eulerData); //Read the data from the sensor
}
/*******************************************************************************************
*Description: This function is used to update the linear acceleration data in m/s2
*Input Parameters: None
*Return Parameter: None
*******************************************************************************************/
void NineAxesMotion::updateLinearAccel(void)
{
BNO055_RETURN_FUNCTION_TYPE comRes = BNO055_ZERO_U8X; //Holds the communication results
comRes = bno055_convert_float_linear_accel_xyz_msq(&linearAccelData); //Read the data from the sensor
}
/*******************************************************************************************
*Description: This function is used to update the gravity acceleration data in m/s2
*Input Parameters: None
*Return Parameter: None
*******************************************************************************************/
void NineAxesMotion::updateGravAccel(void)
{
BNO055_RETURN_FUNCTION_TYPE comRes = BNO055_ZERO_U8X; //Holds the communication results
comRes = bno055_convert_float_gravity_xyz_msq(&gravAccelData); //Read the data from the sensor
}
/*******************************************************************************************
*Description: This function is used to update the calibration status
*Input Parameters: None
*Return Parameter: None
*******************************************************************************************/
void NineAxesMotion::updateCalibStatus(void)
{
BNO055_RETURN_FUNCTION_TYPE comRes = BNO055_ZERO_U8X; //Holds the communication results
comRes = bno055_get_accel_calib_stat(&calibStatus.accel);
comRes = bno055_get_mag_calib_stat(&calibStatus.mag);
comRes = bno055_get_gyro_calib_stat(&calibStatus.gyro);
comRes = bno055_get_sys_calib_stat(&calibStatus.system);
}
/*******************************************************************************************
*Description: This function is used to write the accelerometer configurations
*Input Parameters:
* uint8_t range: To assign the range of the accelerometer
* --------------------------------------
* Constant Definition Constant Value
* --------------------------------------
* ACCEL_RANGE_2G 0X00
* ACCEL_RANGE_4G 0X01
* ACCEL_RANGE_8G 0X02
* ACCEL_RANGE_16G 0X03
* uint8_t bandwidth: To assign the filter bandwidth of the accelerometer
* --------------------------------------
* Constant Definition Constant Value
* --------------------------------------
* ACCEL_BW_7_81HZ 0x00
* ACCEL_BW_15_63HZ 0x01
* ACCEL_BW_31_25HZ 0x02
* ACCEL_BW_62_5HZ 0X03
* ACCEL_BW_125HZ 0X04
* ACCEL_BW_250HZ 0X05
* ACCEL_BW_500HZ 0X06
* ACCEL_BW_1000HZ 0X07
* uint8_t powerMode: To assign the power mode of the accelerometer
* --------------------------------------
* Constant Definition Constant Value
* --------------------------------------
* ACCEL_NORMAL 0X00
* ACCEL_SUSPEND 0X01
* ACCEL_LOWPOWER_1 0X02
* ACCEL_STANDBY 0X03
* ACCEL_LOWPOWER_2 0X04
* ACCEL_DEEPSUSPEND 0X05
*Return Parameter: None
*******************************************************************************************/
void NineAxesMotion::writeAccelConfig(uint8_t range, uint8_t bandwidth, uint8_t powerMode)
{
BNO055_RETURN_FUNCTION_TYPE comRes = BNO055_ZERO_U8X; //Holds the communication results
comRes = bno055_set_accel_range(range);
comRes = bno055_set_accel_bw(bandwidth);
comRes = bno055_set_accel_power_mode(powerMode);
}
/*******************************************************************************************
*Description: This function is used to update the accelerometer configurations
*Input Parameters: None
*Return Parameter: None
*******************************************************************************************/
void NineAxesMotion::updateAccelConfig(void)
{
BNO055_RETURN_FUNCTION_TYPE comRes = BNO055_ZERO_U8X; //Holds the communication results
comRes = bno055_get_accel_range(&accelStatus.range);
comRes = bno055_get_accel_bw(&accelStatus.bandwidth);
comRes = bno055_get_accel_power_mode(&accelStatus.powerMode);
}
/*******************************************************************************************
*Description: This function is used to control which axis of the accelerometer triggers the
* interrupt
*Input Parameters:
* bool xStatus: To know whether the x axis has to trigger the interrupt
* ---------------------------------------------------
* Constant Definition Constant Value Comment
* ---------------------------------------------------
* ENABLE 1 Enables interrupts from that axis
* DISABLE 0 Disables interrupts from that axis
* bool yStatus: To know whether the x axis has to trigger the interrupt
* ---------------------------------------------------
* Constant Definition Constant Value Comment
* ---------------------------------------------------
* ENABLE 1 Enables interrupts from that axis
* DISABLE 0 Disables interrupts from that axis
* bool zStatus: To know whether the x axis has to trigger the interrupt
* ---------------------------------------------------
* Constant Definition Constant Value Comment
* ---------------------------------------------------
* ENABLE 1 Enables interrupts from that axis
* DISABLE 0 Disables interrupts from that axis
*Return Parameter: None
*******************************************************************************************/
void NineAxesMotion::accelInterrupts(bool xStatus, bool yStatus, bool zStatus)
{
BNO055_RETURN_FUNCTION_TYPE comRes = BNO055_ZERO_U8X; //Holds the communication results
comRes = bno055_set_accel_any_motion_no_motion_axis_enable(BNO055_ACCEL_ANY_MOTION_NO_MOTION_X_AXIS, xStatus);
comRes = bno055_set_accel_any_motion_no_motion_axis_enable(BNO055_ACCEL_ANY_MOTION_NO_MOTION_Y_AXIS, yStatus);
comRes = bno055_set_accel_any_motion_no_motion_axis_enable(BNO055_ACCEL_ANY_MOTION_NO_MOTION_Z_AXIS, zStatus);
}
/*******************************************************************************************
*Description: This function is used to reset the interrupt line
*Input Parameters: None
*Return Parameter: None
*******************************************************************************************/
void NineAxesMotion::resetInterrupt(void)
{
BNO055_RETURN_FUNCTION_TYPE comRes = BNO055_ZERO_U8X; //Holds the communication results
comRes = bno055_set_intr_rst(ENABLE);
}
/*******************************************************************************************
*Description: This function is used to enable the any motion interrupt based on the
* accelerometer
*Input Parameters:
* uint8_t threshold: The threshold that triggers the any motion interrupt
* The threshold should be entered as an integer. The corresponding value of
* the threshold depends on the range that has been set on the
* accelerometer. Below is a table showing the value of 1LSB in
* corresponding units.
* Resolution:
* ACCEL_RANGE_2G, 1LSB = 3.91mg = ~0.03835m/s2
* ACCEL_RANGE_4G, 1LSB = 7.81mg = ~0.07661m/s2
* ACCEL_RANGE_8G, 1LSB = 15.6mg = ~0.15303m/s2
* ACCEL_RANGE_16G, 1LSB = 31.3mg = ~0.30705m/s2
* Maximum:
* ACCEL_RANGE_2G, 1LSB = 996mg = ~9.77076m/s2,
* ACCEL_RANGE_4G, 1LSB = 1.99g = ~19.5219m/s2
* ACCEL_RANGE_8G, 1LSB = 3.98g = ~39.0438m/s2
* ACCEL_RANGE_16G, 1LSB = 7.97g = ~97.1857m/s2
* uint8_t duration: The duration for which the desired threshold exist
* The time difference between the successive acceleration signals depends
* on the selected bandwidth and equates to 1/(2*bandwidth).
* In order to suppress false triggers, the interrupt is only generated (cleared)
* if a certain number N of consecutive slope data points is larger (smaller)
* than the slope 'threshold'. This number is set by the 'duration'.
* It is N = duration + 1.
* Resolution:
* ACCEL_BW_7_81HZ, 1LSB = 64ms
* ACCEL_BW_15_63HZ, 1LSB = 32ms
* ACCEL_BW_31_25HZ, 1LSB = 16ms
* ACCEL_BW_62_5HZ, 1LSB = 8ms
* ACCEL_BW_125HZ, 1LSB = 4ms
* ACCEL_BW_250HZ, 1LSB = 2ms
* ACCEL_BW_500HZ, 1LSB = 1ms
* ACCEL_BW_1000HZ, 1LSB = 0.5ms
*Return Parameter: None
*******************************************************************************************/
void NineAxesMotion::enableAnyMotion(uint8_t threshold, uint8_t duration)
{
BNO055_RETURN_FUNCTION_TYPE comRes = BNO055_ZERO_U8X; //Holds the communication results
comRes = bno055_set_accel_any_motion_thres(threshold);
comRes = bno055_set_accel_any_motion_durn(duration);
comRes = bno055_set_intr_accel_any_motion(ENABLE);
comRes = bno055_set_intr_mask_accel_any_motion(ENABLE);
}
/*******************************************************************************************
*Description: This function is used to disable the any motion interrupt
*Input Parameters: None
*Return Parameter: None
*******************************************************************************************/
void NineAxesMotion::disableAnyMotion(void)
{
BNO055_RETURN_FUNCTION_TYPE comRes = BNO055_ZERO_U8X; //Holds the communication results
comRes = bno055_set_intr_accel_any_motion(DISABLE);
comRes = bno055_set_intr_mask_accel_any_motion(DISABLE);
}
/*******************************************************************************************
*Description: This function is used to enable the slow or no motion interrupt based on the
* accelerometer
*Input Parameters:
* uint8_t threshold: The threshold that triggers the no motion interrupt
* The threshold should be entered as an integer. The corresponding value of
* the threshold depends on the range that has been set on the
* accelerometer. Below is a table showing the value of 1LSB in
* corresponding units.
* Resolution:
* ACCEL_RANGE_2G, 1LSB = 3.91mg = ~0.03835m/s2
* ACCEL_RANGE_4G, 1LSB = 7.81mg = ~0.07661m/s2
* ACCEL_RANGE_8G, 1LSB = 15.6mg = ~0.15303m/s2
* ACCEL_RANGE_16G, 1LSB = 31.3mg = ~0.30705m/s2
* Maximum:
* ACCEL_RANGE_2G, 1LSB = 996mg = ~9.77076m/s2,
* ACCEL_RANGE_4G, 1LSB = 1.99g = ~19.5219m/s2
* ACCEL_RANGE_8G, 1LSB = 3.98g = ~39.0438m/s2
* ACCEL_RANGE_16G, 1LSB = 7.97g = ~97.1857m/s2
* uint8_t duration: The duration for which the desired threshold should be surpassed
* The time difference between the successive acceleration signals depends
* on the selected bandwidth and equates to 1/(2*bandwidth).
* In order to suppress false triggers, the interrupt is only generated (cleared)
* if a certain number N of consecutive slope data points is larger (smaller)
* than the slope 'threshold'. This number is set by the 'duration'.
* It is N = duration + 1.
* Resolution:
* ACCEL_BW_7_81HZ, 1LSB = 64ms
* ACCEL_BW_15_63HZ, 1LSB = 32ms
* ACCEL_BW_31_25HZ, 1LSB = 16ms
* ACCEL_BW_62_5HZ, 1LSB = 8ms
* ACCEL_BW_125HZ, 1LSB = 4ms
* ACCEL_BW_250HZ, 1LSB = 2ms
* ACCEL_BW_500HZ, 1LSB = 1ms
* ACCEL_BW_1000HZ, 1LSB = 0.5ms
* bool motion: To trigger either a Slow motion or a No motion interrupt
* ---------------------------------------------------
* Constant Definition Constant Value Comment
* ---------------------------------------------------
* NO_MOTION 1 Enables the no motion interrupt
* SLOW_MOTION 0 Enables the slow motion interrupt
*Return Parameter: None
*******************************************************************************************/
void NineAxesMotion::enableSlowNoMotion(uint8_t threshold, uint8_t duration, bool motion)
{
BNO055_RETURN_FUNCTION_TYPE comRes = BNO055_ZERO_U8X; //Holds the communication results
comRes = bno055_set_accel_slow_no_motion_enable(motion);
comRes = bno055_set_accel_slow_no_motion_thres(threshold);
comRes = bno055_set_accel_slow_no_motion_durn(duration);
comRes = bno055_set_intr_accel_no_motion(ENABLE);
comRes = bno055_set_intr_mask_accel_no_motion(ENABLE);
}
/*******************************************************************************************
*Description: This function is used to disable the slow or no motion interrupt
*Input Parameters: None
*Return Parameter: None
*******************************************************************************************/
void NineAxesMotion::disableSlowNoMotion(void)
{
BNO055_RETURN_FUNCTION_TYPE comRes = BNO055_ZERO_U8X; //Holds the communication results
comRes = bno055_set_intr_accel_no_motion(DISABLE);
comRes = bno055_set_intr_mask_accel_any_motion(DISABLE);
}
/*******************************************************************************************
*Description: This function is used to change the mode of updating the local data
*Input Parameters: None
*Return Parameter: None
*******************************************************************************************/
void NineAxesMotion::setUpdateMode(bool updateMode)
{
dataUpdateMode = updateMode;
}
/*******************************************************************************************
*Description: This function is used to return the x-axis of the accelerometer data
*Input Parameters: None
*Return Parameter:
* float: X-axis accelerometer data in m/s2
*******************************************************************************************/
float NineAxesMotion::readAccelX(void)
{
if (dataUpdateMode == AUTO)
{
updateAccel();
}
return accelData.x;
}
/*******************************************************************************************
*Description: This function is used to return the y-axis of the accelerometer data
*Input Parameters: None
*Return Parameter:
* float: Y-axis accelerometer data in m/s2
*******************************************************************************************/
float NineAxesMotion::readAccelY(void)
{
if (dataUpdateMode == AUTO)
{
updateAccel();
}
return accelData.y;
}
/*******************************************************************************************
*Description: This function is used to return the z-axis of the accelerometer data
*Input Parameters: None
*Return Parameter:
* float: Z-axis accelerometer data in m/s2
*******************************************************************************************/
float NineAxesMotion::readAccelZ(void)
{
if (dataUpdateMode == AUTO)
{
updateAccel();
}
return accelData.z;
}
/*******************************************************************************************
*Description: This function is used to return the x-axis of the gyroscope data
*Input Parameters: None
*Return Parameter:
* float: X-axis gyroscope data in deg/s
*******************************************************************************************/
float NineAxesMotion::readGyroX(void)
{
if (dataUpdateMode == AUTO)
{
updateGyro();
}
return gyroData.x;
}
/*******************************************************************************************
*Description: This function is used to return the y-axis of the gyroscope data
*Input Parameters: None
*Return Parameter:
* float: Y-axis gyroscope data in deg/s
*******************************************************************************************/
float NineAxesMotion::readGyroY(void)
{
if (dataUpdateMode == AUTO)
{
updateGyro();
}
return gyroData.y;
}
/*******************************************************************************************
*Description: This function is used to return the z-axis of the gyroscope data
*Input Parameters: None
*Return Parameter:
* float: Z-axis gyroscope data in deg/s
*******************************************************************************************/
float NineAxesMotion::readGyroZ(void)
{
if (dataUpdateMode == AUTO)
{
updateGyro();
}
return gyroData.z;
}
/*******************************************************************************************
*Description: This function is used to return the x-axis of the magnetometer data
*Input Parameters: None
*Return Parameter:
* float: X-axis magnetometer data in �T
*******************************************************************************************/
float NineAxesMotion::readMagX(void)
{
if (dataUpdateMode == AUTO)
{
updateMag();
}
return magData.x;
}
/*******************************************************************************************
*Description: This function is used to return the y-axis of the magnetometer data
*Input Parameters: None
*Return Parameter:
* float: Y-axis magnetometer data in �T
*******************************************************************************************/
float NineAxesMotion::readMagY(void)
{
if (dataUpdateMode == AUTO)
{
updateMag();
}
return magData.y;
}
/*******************************************************************************************
*Description: This function is used to return the z-axis of the magnetometer data
*Input Parameters: None
*Return Parameter:
* float: Z-axis magnetometer data in �T
*******************************************************************************************/
float NineAxesMotion::readMagZ(void)
{
if (dataUpdateMode == AUTO)
{
updateMag();
}
return magData.z;
}
/*******************************************************************************************
*Description: This function is used to return the w-axis of the quaternion data
*Input Parameters: None
*Return Parameter:
* int16_t: W-axis quaternion data multiplied by 1000 (for 3 decimal places accuracy)
*******************************************************************************************/
int16_t NineAxesMotion::readQuatW(void)
{
if (dataUpdateMode == AUTO)
{
updateQuat();
}
return quatData.w;
}
/*******************************************************************************************
*Description: This function is used to return the x-axis of the quaternion data
*Input Parameters: None
*Return Parameter:
* int16_t: X-axis quaternion data multiplied by 1000 (for 3 decimal places accuracy)
*******************************************************************************************/
int16_t NineAxesMotion::readQuatX(void)
{
if (dataUpdateMode == AUTO)
{
updateQuat();
}
return quatData.x;
}
/*******************************************************************************************
*Description: This function is used to return the y-axis of the quaternion data
*Input Parameters: None
*Return Parameter:
* int16_t: Y-axis quaternion data multiplied by 1000 (for 3 decimal places accuracy)
*******************************************************************************************/
int16_t NineAxesMotion::readQuatY(void)
{
if (dataUpdateMode == AUTO)
{
updateQuat();
}
return quatData.y;
}
/*******************************************************************************************
*Description: This function is used to return the z-axis of the quaternion data
*Input Parameters: None
*Return Parameter:
* int16_t: Z-axis quaternion data multiplied by 1000 (for 3 decimal places accuracy)
*******************************************************************************************/
int16_t NineAxesMotion::readQuatZ(void)
{
if (dataUpdateMode == AUTO)
{
updateQuat();
}
return quatData.z;
}
/*******************************************************************************************
*Description: This function is used to return the heading(yaw) of the euler data
*Input Parameters: None
*Return Parameter:
* float: Heading of the euler data
*******************************************************************************************/
float NineAxesMotion::readEulerHeading(void)
{
if (dataUpdateMode == AUTO)
{
updateEuler();
}
return eulerData.h;
}
/*******************************************************************************************
*Description: This function is used to return the roll of the euler data
*Input Parameters: None
*Return Parameter:
* float: Roll of the euler data
*******************************************************************************************/
float NineAxesMotion::readEulerRoll(void)
{
if (dataUpdateMode == AUTO)
{
updateEuler();
}
return eulerData.r;
}
/*******************************************************************************************
*Description: This function is used to return the pitch of the euler data
*Input Parameters: None
*Return Parameter:
* float: Pitch of the euler data
*******************************************************************************************/
float NineAxesMotion::readEulerPitch(void)
{
if (dataUpdateMode == AUTO)
{
updateEuler();
}
return eulerData.p;
}
/*******************************************************************************************
*Description: This function is used to return the x-axis of the linear acceleration data
* (accelerometer data without the gravity vector)
*Input Parameters: None
*Return Parameter:
* float: X-axis Linear Acceleration data in m/s2
*******************************************************************************************/
float NineAxesMotion::readLinearAccelX(void)
{
if (dataUpdateMode == AUTO)
{
updateLinearAccel();
}
return linearAccelData.x;
}
/*******************************************************************************************
*Description: This function is used to return the y-axis of the linear acceleration data
* (accelerometer data without the gravity vector)
*Input Parameters: None
*Return Parameter:
* float: Y-axis Linear Acceleration data in m/s2
*******************************************************************************************/
float NineAxesMotion::readLinearAccelY(void)
{
if (dataUpdateMode == AUTO)
{
updateLinearAccel();
}
return linearAccelData.y;
}
/*******************************************************************************************
*Description: This function is used to return the z-axis of the linear acceleration data
* (accelerometer data without the gravity vector)
*Input Parameters: None
*Return Parameter:
* float: Z-axis Linear Acceleration data in m/s2
*******************************************************************************************/
float NineAxesMotion::readLinearAccelZ(void)
{
if (dataUpdateMode == AUTO)
{
updateLinearAccel();
}
return linearAccelData.z;
}
/*******************************************************************************************
*Description: This function is used to return the x-axis of the gravity acceleration data
* (accelerometer data with only the gravity vector)
*Input Parameters: None
*Return Parameter:
* float: X-axis Gravity Acceleration data in m/s2
*******************************************************************************************/
float NineAxesMotion::readGravAccelX(void)
{
if (dataUpdateMode == AUTO)
{
updateGravAccel();
}
return gravAccelData.x;
}
/*******************************************************************************************
*Description: This function is used to return the y-axis of the gravity acceleration data
* (accelerometer data with only the gravity vector)
*Input Parameters: None
*Return Parameter:
* float: Y-axis Gravity Acceleration data in m/s2
*******************************************************************************************/
float NineAxesMotion::readGravAccelY(void)
{
if (dataUpdateMode == AUTO)
{
updateGravAccel();
}
return gravAccelData.y;
}
/*******************************************************************************************
*Description: This function is used to return the z-axis of the gravity acceleration data
* (accelerometer data with only the gravity vector)
*Input Parameters: None
*Return Parameter:
* float: Z-axis Gravity Acceleration data in m/s2
*******************************************************************************************/
float NineAxesMotion::readGravAccelZ(void)
{
if (dataUpdateMode == AUTO)
{
updateGravAccel();
}
return gravAccelData.z;
}
/*******************************************************************************************
*Description: This function is used to return the accelerometer calibration status
*Input Parameters: None
*Return Parameter:
* uint8_t: Accelerometer calibration status, 0-3 (0 - low, 3 - high)
*******************************************************************************************/
uint8_t NineAxesMotion::readAccelCalibStatus(void)
{
if (dataUpdateMode == AUTO)
{
updateCalibStatus();
}
return calibStatus.accel;
}
/*******************************************************************************************
*Description: This function is used to return the gyroscope calibration status
*Input Parameters: None
*Return Parameter:
* uint8_t: Gyroscope calibration status, 0-3 (0 - low, 3 - high)
*******************************************************************************************/
uint8_t NineAxesMotion::readGyroCalibStatus(void)
{
if (dataUpdateMode == AUTO)
{
updateCalibStatus();
}
return calibStatus.gyro;
}
/*******************************************************************************************
*Description: This function is used to return the magnetometer calibration status
*Input Parameters: None
*Return Parameter:
* uint8_t: Magnetometer calibration status, 0-3 (0 - low, 3 - high)
*******************************************************************************************/
uint8_t NineAxesMotion::readMagCalibStatus(void)
{
if (dataUpdateMode == AUTO)
{
updateCalibStatus();
}
return calibStatus.mag;
}
/*******************************************************************************************
*Description: This function is used to return the system calibration status
*Input Parameters: None
*Return Parameter:
* uint8_t: System calibration status, 0-3 (0 - low, 3 - high)
*******************************************************************************************/
uint8_t NineAxesMotion::readSystemCalibStatus(void)
{
if (dataUpdateMode == AUTO)
{
updateCalibStatus();
}
return calibStatus.system;
}
/*******************************************************************************************
*Description: This function is used to return the accelerometer range
*Input Parameters: None
*Return Parameter:
* uint8_t range: Range of the accelerometer
* --------------------------------------
* Constant Definition Constant Value
* --------------------------------------
* ACCEL_RANGE_2G 0X00
* ACCEL_RANGE_4G 0X01
* ACCEL_RANGE_8G 0X02
* ACCEL_RANGE_16G 0X03
*******************************************************************************************/
uint8_t NineAxesMotion::readAccelRange(void)
{
if (dataUpdateMode == AUTO)
{
updateAccelConfig();
}
return accelStatus.range;
}
/*******************************************************************************************
*Description: This function is used to return the accelerometer bandwidth
*Input Parameters: None
*Return Parameter:
* uint8_t bandwidth: Bandwidth of the accelerometer
* --------------------------------------
* Constant Definition Constant Value
* --------------------------------------
* ACCEL_BW_7_81HZ 0x00
* ACCEL_BW_15_63HZ 0x01
* ACCEL_BW_31_25HZ 0x02
* ACCEL_BW_62_5HZ 0X03
* ACCEL_BW_125HZ 0X04
* ACCEL_BW_250HZ 0X05
* ACCEL_BW_500HZ 0X06
* ACCEL_BW_1000HZ 0X07
*******************************************************************************************/
uint8_t NineAxesMotion::readAccelBandwidth(void)
{
if (dataUpdateMode == AUTO)
{
updateAccelConfig();
}
return accelStatus.bandwidth;
}
/*******************************************************************************************
*Description: This function is used to return the accelerometer power mode
*Input Parameters: None
*Return Parameter:
* uint8_t powerMode: Power mode of the accelerometer
* --------------------------------------
* Constant Definition Constant Value
* --------------------------------------
* ACCEL_NORMAL 0X00
* ACCEL_SUSPEND 0X01
* ACCEL_LOWPOWER_1 0X02
* ACCEL_STANDBY 0X03
* ACCEL_LOWPOWER_2 0X04
* ACCEL_DEEPSUSPEND 0X05
*******************************************************************************************/
uint8_t NineAxesMotion::readAccelPowerMode(void)
{
if (dataUpdateMode == AUTO)
{
updateAccelConfig();
}
return accelStatus.powerMode;
}
/******************** Bridge Functions for the Sensor API to control the Arduino Hardware******************************************/
signed char BNO055_I2C_bus_read(unsigned char dev_addr,unsigned char reg_addr, unsigned char *reg_data, unsigned char cnt)
{
BNO055_RETURN_FUNCTION_TYPE comres = BNO055_ZERO_U8X;
I2C.beginTransmission(dev_addr); //Start of transmission
I2C.write(reg_addr); //Desired start register
comres = I2C.endTransmission(); //Stop of transmission
delayMicroseconds(150); //Caution Delay
I2C.requestFrom(dev_addr, cnt); //Request data
while(I2C.available()) //The slave device may send less than requested (burst read)
{
*reg_data = I2C.read(); //Receive a byte
reg_data++; //Increment pointer
}
return comres;
}
signed char BNO055_I2C_bus_write(unsigned char dev_addr,unsigned char reg_addr, unsigned char *reg_data, unsigned char cnt)
{
BNO055_RETURN_FUNCTION_TYPE comres = BNO055_ZERO_U8X;
I2C.beginTransmission(dev_addr); //Start of transmission
I2C.write(reg_addr); //Desired start register
for(unsigned char index = 0; index < cnt; index++) //Note that the BNO055 supports burst write
{
I2C.write(*reg_data); //Write the data
reg_data++; //Increment pointer
}
comres = I2C.endTransmission(); //Stop of transmission
delayMicroseconds(150); //Caution Delay
return comres;
}
void _delay(u_32 period)
{
delay(period);
}