-
Notifications
You must be signed in to change notification settings - Fork 2
/
Copy pathBNO08x_AOG.cpp
1617 lines (1394 loc) · 51.6 KB
/
BNO08x_AOG.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
/*
This is a library written for the BNO080
SparkFun sells these at its website: www.sparkfun.com
Do you like this library? Help support SparkFun. Buy a board!
https://www.sparkfun.com/products/14686
Written by Nathan Seidle @ SparkFun Electronics, December 28th, 2017
Edited by Math for AgOpenGPS application
The BNO080 IMU is a powerful triple axis gyro/accel/magnetometer coupled with an ARM processor
to maintain and complete all the complex calculations for various VR, inertial, step counting,
and movement operations.
This library handles the initialization of the BNO080 and is able to query the sensor
for different readings.
https://github.com/sparkfun/SparkFun_BNO080_Arduino_Library
Development environment specifics:
Arduino IDE 1.8.5
This program 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 this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "BNO08x_AOG.h"
//Attempt communication with the device
//Return true if we got a 'Polo' back from Marco
boolean BNO080::begin(uint8_t deviceAddress, TwoWire &wirePort, uint8_t intPin)
{
_deviceAddress = deviceAddress; //If provided, store the I2C address from user
_i2cPort = &wirePort; //Grab which port the user wants us to use
_int = intPin; //Get the pin that the user wants to use for interrupts. By default, it's NULL and we'll not use it in dataAvailable() function.
//We expect caller to begin their I2C port, with the speed of their choice external to the library
//But if they forget, we start the hardware here.
//_i2cPort->begin();
//Begin by resetting the IMU
softReset();
//Check communication with device
shtpData[0] = SHTP_REPORT_PRODUCT_ID_REQUEST; //Request the product ID and reset info
shtpData[1] = 0; //Reserved
//Transmit packet on channel 2, 2 bytes
sendPacket(CHANNEL_CONTROL, 2);
//Now we wait for response
if (receivePacket() == true)
{
if (shtpData[0] == SHTP_REPORT_PRODUCT_ID_RESPONSE)
{
if (_printDebug == true)
{
_debugPort->print(F("SW Version Major: 0x"));
_debugPort->print(shtpData[2], HEX);
_debugPort->print(F(" SW Version Minor: 0x"));
_debugPort->print(shtpData[3], HEX);
uint32_t SW_Part_Number = ((uint32_t)shtpData[7] << 24) | ((uint32_t)shtpData[6] << 16) | ((uint32_t)shtpData[5] << 8) | ((uint32_t)shtpData[4]);
_debugPort->print(F(" SW Part Number: 0x"));
_debugPort->print(SW_Part_Number, HEX);
uint32_t SW_Build_Number = ((uint32_t)shtpData[11] << 24) | ((uint32_t)shtpData[10] << 16) | ((uint32_t)shtpData[9] << 8) | ((uint32_t)shtpData[8]);
_debugPort->print(F(" SW Build Number: 0x"));
_debugPort->print(SW_Build_Number, HEX);
uint16_t SW_Version_Patch = ((uint16_t)shtpData[13] << 8) | ((uint16_t)shtpData[12]);
_debugPort->print(F(" SW Version Patch: 0x"));
_debugPort->println(SW_Version_Patch, HEX);
}
return (true);
}
}
return (false); //Something went wrong
}
boolean BNO080::beginSPI(uint8_t user_CSPin, uint8_t user_WAKPin, uint8_t user_INTPin, uint8_t user_RSTPin, uint32_t spiPortSpeed, SPIClass &spiPort)
{
_i2cPort = NULL; //This null tells the send/receive functions to use SPI
//Get user settings
_spiPort = &spiPort;
_spiPortSpeed = spiPortSpeed;
if (_spiPortSpeed > 3000000)
_spiPortSpeed = 3000000; //BNO080 max is 3MHz
_cs = user_CSPin;
_wake = user_WAKPin;
_int = user_INTPin;
_rst = user_RSTPin;
pinMode(_cs, OUTPUT);
pinMode(_wake, OUTPUT);
pinMode(_int, INPUT_PULLUP);
pinMode(_rst, OUTPUT);
digitalWrite(_cs, HIGH); //Deselect BNO080
//Configure the BNO080 for SPI communication
digitalWrite(_wake, HIGH); //Before boot up the PS0/WAK pin must be high to enter SPI mode
digitalWrite(_rst, LOW); //Reset BNO080
delay(2); //Min length not specified in datasheet?
digitalWrite(_rst, HIGH); //Bring out of reset
//Wait for first assertion of INT before using WAK pin. Can take ~104ms
waitForSPI();
//if(wakeBNO080() == false) //Bring IC out of sleep after reset
// Serial.println("BNO080 did not wake up");
_spiPort->begin(); //Turn on SPI hardware
//At system startup, the hub must send its full advertisement message (see 5.2 and 5.3) to the
//host. It must not send any other data until this step is complete.
//When BNO080 first boots it broadcasts big startup packet
//Read it and dump it
waitForSPI(); //Wait for assertion of INT before reading advert message.
receivePacket();
//The BNO080 will then transmit an unsolicited Initialize Response (see 6.4.5.2)
//Read it and dump it
waitForSPI(); //Wait for assertion of INT before reading Init response
receivePacket();
//Check communication with device
shtpData[0] = SHTP_REPORT_PRODUCT_ID_REQUEST; //Request the product ID and reset info
shtpData[1] = 0; //Reserved
//Transmit packet on channel 2, 2 bytes
sendPacket(CHANNEL_CONTROL, 2);
//Now we wait for response
waitForSPI();
if (receivePacket() == true)
{
if (shtpData[0] == SHTP_REPORT_PRODUCT_ID_RESPONSE)
if (_printDebug == true)
{
_debugPort->print(F("SW Version Major: 0x"));
_debugPort->print(shtpData[2], HEX);
_debugPort->print(F(" SW Version Minor: 0x"));
_debugPort->print(shtpData[3], HEX);
uint32_t SW_Part_Number = ((uint32_t)shtpData[7] << 24) | ((uint32_t)shtpData[6] << 16) | ((uint32_t)shtpData[5] << 8) | ((uint32_t)shtpData[4]);
_debugPort->print(F(" SW Part Number: 0x"));
_debugPort->print(SW_Part_Number, HEX);
uint32_t SW_Build_Number = ((uint32_t)shtpData[11] << 24) | ((uint32_t)shtpData[10] << 16) | ((uint32_t)shtpData[9] << 8) | ((uint32_t)shtpData[8]);
_debugPort->print(F(" SW Build Number: 0x"));
_debugPort->print(SW_Build_Number, HEX);
uint16_t SW_Version_Patch = ((uint16_t)shtpData[13] << 8) | ((uint16_t)shtpData[12]);
_debugPort->print(F(" SW Version Patch: 0x"));
_debugPort->println(SW_Version_Patch, HEX);
}
return (true);
}
return (false); //Something went wrong
}
//Calling this function with nothing sets the debug port to Serial
//You can also call it with other streams like Serial1, SerialUSB, etc.
void BNO080::enableDebugging(Stream &debugPort)
{
_debugPort = &debugPort;
_printDebug = true;
}
//Updates the latest variables if possible
//Returns false if new readings are not available
bool BNO080::dataAvailable(void)
{
//If we have an interrupt pin connection available, check if data is available.
//If int pin is not set, then we'll rely on receivePacket() to timeout
//See issue 13: https://github.com/sparkfun/SparkFun_BNO080_Arduino_Library/issues/13
if (_int != 255)
{
if (digitalRead(_int) == HIGH)
return (false);
}
if (receivePacket() == true)
{
//Check to see if this packet is a sensor reporting its data to us
if (shtpHeader[2] == CHANNEL_REPORTS && shtpData[0] == SHTP_REPORT_BASE_TIMESTAMP)
{
parseInputReport(); //This will update the rawAccelX, etc variables depending on which feature report is found
return (true);
}
else if (shtpHeader[2] == CHANNEL_CONTROL)
{
parseCommandReport(); //This will update responses to commands, calibrationStatus, etc.
return (true);
}
else if (shtpHeader[2] == CHANNEL_GYRO)
{
parseInputReport(); //This will update the rawAccelX, etc variables depending on which feature report is found
return (true);
}
}
return (false);
}
//This function pulls the data from the command response report or get feature response report
//Unit responds with packet that contains the following:
// Command response report | Get feature respond report
//shtpHeader[0:3]: First, a 4 byte header | First, a 4 byte header
//shtpData[0]: The Report ID | The Report ID
//shtpData[1]: Sequence number (See 6.5.18.2) | Feature report ID
//shtpData[2]: Command | Feature flags
//shtpData[3]: Command Sequence Number | Change sensitivity [absolute | relative] LSB
//shtpData[4]: Response Sequence Number | Change sensitivity [absolute | relative] MSB
//shtpData[5 + 0]: R0 | Report Interval LSB
//shtpData[5 + 1]: R1 | Report Interval
//shtpData[5 + 2]: R2 | Report Interval
//shtpData[5 + 3]: R3 | Report Interval MSB
//shtpData[5 + 4]: R4 | Batch Interval LSB
//shtpData[5 + 5]: R5 | Batch Interval
//shtpData[5 + 6]: R6 | Batch Interval
//shtpData[5 + 7]: R7 | Batch Interval MSB
//shtpData[5 + 8]: R8
void BNO080::parseCommandReport(void)
{
if (shtpData[0] == SHTP_REPORT_COMMAND_RESPONSE)
{
//The BNO080 responds with this report to command requests. It's up to use to remember which command we issued.
uint8_t command = shtpData[2]; //This is the Command byte of the response
if (command == COMMAND_ME_CALIBRATE)
{
calibrationStatus = shtpData[5 + 0]; //R0 - Status (0 = success, non-zero = fail)
//Add by Math : 4 followings lines for printMECalibrationRespond() function
calibrationAccEnable = shtpData[5 + 1]; // R1 - Accel Cal Enable (1 – enabled, 0 – disabled)
calibrationGyroEnable = shtpData[5 + 2]; // R2 - Gyro Cal Enable (1 – enabled, 0 – disabled)
calibrationMagnEnable = shtpData[5 + 3]; // R3 - Mag Cal Enable (1 – enabled, 0 – disabled)
calibrationPlanEnable = shtpData[5 + 4]; // R4 - Planar Accel Cal Enable (1 – enabled, 0 – disabled)
}
}
//Add by Math: retrieve of the BNO08x report Get Feature Response
else if (shtpData[0] == SHTP_REPORT_GET_FEATURE_RESPONSE)
{
featureReportId = shtpData[1];
reportInterval = (long)shtpData[8] << 24 | (long)shtpData[7] << 16 | (uint16_t)shtpData[6] << 8 | shtpData[5];
}
//Add by Math: end
else
{
//This sensor report ID is unhandled.
//See reference manual to add additional feature reports as needed
}
//TODO additional feature reports may be strung together. Parse them all.
}
//This function pulls the data from the input report
//The input reports vary in length so this function stores the various 16-bit values as globals
//Unit responds with packet that contains the following:
//shtpHeader[0:3]: First, a 4 byte header
//shtpData[0:4]: Then a 5 byte timestamp of microsecond clicks since reading was taken
//shtpData[5 + 0]: Then a feature report ID (0x01 for Accel, 0x05 for Rotation Vector)
//shtpData[5 + 1]: Sequence number (See 6.5.18.2)
//shtpData[5 + 2]: Status
//shtpData[3]: Delay
//shtpData[4:5]: i/accel x/gyro x/etc
//shtpData[6:7]: j/accel y/gyro y/etc
//shtpData[8:9]: k/accel z/gyro z/etc
//shtpData[10:11]: real/gyro temp/etc
//shtpData[12:13]: Accuracy estimate
void BNO080::parseInputReport(void)
{
//Calculate the number of data bytes in this packet
int16_t dataLength = ((uint16_t)shtpHeader[1] << 8 | shtpHeader[0]);
dataLength &= ~(1 << 15); //Clear the MSbit. This bit indicates if this package is a continuation of the last.
//Ignore it for now. TODO catch this as an error and exit
dataLength -= 4; //Remove the header bytes from the data count
timeStamp = ((uint32_t)shtpData[4] << (8 * 3)) | ((uint32_t)shtpData[3] << (8 * 2)) | ((uint32_t)shtpData[2] << (8 * 1)) | ((uint32_t)shtpData[1] << (8 * 0));
// The gyro-integrated input reports are sent via the special gyro channel and do no include the usual ID, sequence, and status fields
if (shtpHeader[2] == CHANNEL_GYRO) {
rawQuatI = (uint16_t)shtpData[1] << 8 | shtpData[0];
rawQuatJ = (uint16_t)shtpData[3] << 8 | shtpData[2];
rawQuatK = (uint16_t)shtpData[5] << 8 | shtpData[4];
rawQuatReal = (uint16_t)shtpData[7] << 8 | shtpData[6];
rawFastGyroX = (uint16_t)shtpData[9] << 8 | shtpData[8];
rawFastGyroY = (uint16_t)shtpData[11] << 8 | shtpData[10];
rawFastGyroZ = (uint16_t)shtpData[13] << 8 | shtpData[12];
return;
}
uint8_t status = shtpData[5 + 2] & 0x03; //Get status bits
uint16_t data1 = (uint16_t)shtpData[5 + 5] << 8 | shtpData[5 + 4];
uint16_t data2 = (uint16_t)shtpData[5 + 7] << 8 | shtpData[5 + 6];
uint16_t data3 = (uint16_t)shtpData[5 + 9] << 8 | shtpData[5 + 8];
uint16_t data4 = 0;
uint16_t data5 = 0; //We would need to change this to uin32_t to capture time stamp value on Raw Accel/Gyro/Mag reports
if (dataLength - 5 > 9)
{
data4 = (uint16_t)shtpData[5 + 11] << 8 | shtpData[5 + 10];
}
if (dataLength - 5 > 11)
{
data5 = (uint16_t)shtpData[5 + 13] << 8 | shtpData[5 + 12];
}
//Store these generic values to their proper global variable
if (shtpData[5] == SENSOR_REPORTID_ACCELEROMETER)
{
accelAccuracy = status;
rawAccelX = data1;
rawAccelY = data2;
rawAccelZ = data3;
}
else if (shtpData[5] == SENSOR_REPORTID_LINEAR_ACCELERATION)
{
accelLinAccuracy = status;
rawLinAccelX = data1;
rawLinAccelY = data2;
rawLinAccelZ = data3;
}
else if (shtpData[5] == SENSOR_REPORTID_GYROSCOPE)
{
gyroAccuracy = status;
rawGyroX = data1;
rawGyroY = data2;
rawGyroZ = data3;
}
else if (shtpData[5] == SENSOR_REPORTID_MAGNETIC_FIELD)
{
magAccuracy = status;
rawMagX = data1;
rawMagY = data2;
rawMagZ = data3;
}
else if (shtpData[5] == SENSOR_REPORTID_ROTATION_VECTOR ||
shtpData[5] == SENSOR_REPORTID_GAME_ROTATION_VECTOR ||
shtpData[5] == SENSOR_REPORTID_AR_VR_STABILIZED_ROTATION_VECTOR ||
shtpData[5] == SENSOR_REPORTID_AR_VR_STABILIZED_GAME_ROTATION_VECTOR)
{
quatAccuracy = status;
rawQuatI = data1;
rawQuatJ = data2;
rawQuatK = data3;
rawQuatReal = data4;
//Only available on rotation vector and ar/vr stabilized rotation vector,
// not game rot vector and not ar/vr stabilized rotation vector
rawQuatRadianAccuracy = data5;
}
else if (shtpData[5] == SENSOR_REPORTID_STEP_COUNTER)
{
stepCount = data3; //Bytes 8/9
}
else if (shtpData[5] == SENSOR_REPORTID_STABILITY_CLASSIFIER)
{
stabilityClassifier = shtpData[5 + 4]; //Byte 4 only
}
else if (shtpData[5] == SENSOR_REPORTID_PERSONAL_ACTIVITY_CLASSIFIER)
{
activityClassifier = shtpData[5 + 5]; //Most likely state
//Load activity classification confidences into the array
for (uint8_t x = 0; x < 9; x++) //Hardcoded to max of 9. TODO - bring in array size
_activityConfidences[x] = shtpData[5 + 6 + x]; //5 bytes of timestamp, byte 6 is first confidence byte
}
else if (shtpData[5] == SENSOR_REPORTID_RAW_ACCELEROMETER)
{
memsRawAccelX = data1;
memsRawAccelY = data2;
memsRawAccelZ = data3;
}
else if (shtpData[5] == SENSOR_REPORTID_RAW_GYROSCOPE)
{
memsRawGyroX = data1;
memsRawGyroY = data2;
memsRawGyroZ = data3;
}
else if (shtpData[5] == SENSOR_REPORTID_RAW_MAGNETOMETER)
{
memsRawMagX = data1;
memsRawMagY = data2;
memsRawMagZ = data3;
}
else if (shtpData[5] == SHTP_REPORT_COMMAND_RESPONSE)
{
if (_printDebug == true)
{
_debugPort->println(F("!"));
}
//The BNO080 responds with this report to command requests. It's up to use to remember which command we issued.
uint8_t command = shtpData[5 + 2]; //This is the Command byte of the response
if (command == COMMAND_ME_CALIBRATE)
{
if (_printDebug == true)
{
_debugPort->println(F("ME Cal report found!"));
}
calibrationStatus = shtpData[5 + 5]; //R0 - Status (0 = success, non-zero = fail)
}
}
else
{
//This sensor report ID is unhandled.
//See reference manual to add additional feature reports as needed
}
//TODO additional feature reports may be strung together. Parse them all.
}
// Quaternion to Euler conversion
// https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles
// https://github.com/sparkfun/SparkFun_MPU-9250-DMP_Arduino_Library/issues/5#issuecomment-306509440
// Return the roll (rotation around the x-axis) in Radians
float BNO080::getRoll()
{
float dqw = getQuatReal();
float dqx = getQuatI();
float dqy = getQuatJ();
float dqz = getQuatK();
float norm = sqrt(dqw * dqw + dqx * dqx + dqy * dqy + dqz * dqz);
dqw = dqw / norm;
dqx = dqx / norm;
dqy = dqy / norm;
dqz = dqz / norm;
float ysqr = dqy * dqy;
// roll (x-axis rotation)
float t0 = +2.0 * (dqw * dqx + dqy * dqz);
float t1 = +1.0 - 2.0 * (dqx * dqx + ysqr);
float roll = atan2(t0, t1);
return (roll);
}
// Return the pitch (rotation around the y-axis) in Radians
float BNO080::getPitch()
{
float dqw = getQuatReal();
float dqx = getQuatI();
float dqy = getQuatJ();
float dqz = getQuatK();
float norm = sqrt(dqw * dqw + dqx * dqx + dqy * dqy + dqz * dqz);
dqw = dqw / norm;
dqx = dqx / norm;
dqy = dqy / norm;
dqz = dqz / norm;
//float ysqr = dqy * dqy; Brian Tee unused variable ysqr
// pitch (y-axis rotation)
float t2 = +2.0 * (dqw * dqy - dqz * dqx);
t2 = t2 > 1.0 ? 1.0 : t2;
t2 = t2 < -1.0 ? -1.0 : t2;
float pitch = asin(t2);
return (pitch);
}
// Return the yaw / heading (rotation around the z-axis) in Radians
float BNO080::getYaw()
{
float dqw = getQuatReal();
float dqx = getQuatI();
float dqy = getQuatJ();
float dqz = getQuatK();
float norm = sqrt(dqw * dqw + dqx * dqx + dqy * dqy + dqz * dqz);
dqw = dqw / norm;
dqx = dqx / norm;
dqy = dqy / norm;
dqz = dqz / norm;
float ysqr = dqy * dqy;
// yaw (z-axis rotation)
float t3 = +2.0 * (dqw * dqz + dqx * dqy);
float t4 = +1.0 - 2.0 * (ysqr + dqz * dqz);
float yaw = atan2(t3, t4);
return (yaw);
}
//Return the rotation vector quaternion I
float BNO080::getQuatI()
{
float quat = qToFloat(rawQuatI, rotationVector_Q1);
return (quat);
}
//Return the rotation vector quaternion J
float BNO080::getQuatJ()
{
float quat = qToFloat(rawQuatJ, rotationVector_Q1);
return (quat);
}
//Return the rotation vector quaternion K
float BNO080::getQuatK()
{
float quat = qToFloat(rawQuatK, rotationVector_Q1);
return (quat);
}
//Return the rotation vector quaternion Real
float BNO080::getQuatReal()
{
float quat = qToFloat(rawQuatReal, rotationVector_Q1);
return (quat);
}
//Return the rotation vector accuracy
float BNO080::getQuatRadianAccuracy()
{
float quat = qToFloat(rawQuatRadianAccuracy, rotationVectorAccuracy_Q1);
return (quat);
}
//Return the acceleration component
uint8_t BNO080::getQuatAccuracy()
{
return (quatAccuracy);
}
//Return the acceleration component
float BNO080::getAccelX()
{
float accel = qToFloat(rawAccelX, accelerometer_Q1);
return (accel);
}
//Return the acceleration component
float BNO080::getAccelY()
{
float accel = qToFloat(rawAccelY, accelerometer_Q1);
return (accel);
}
//Return the acceleration component
float BNO080::getAccelZ()
{
float accel = qToFloat(rawAccelZ, accelerometer_Q1);
return (accel);
}
//Return the acceleration component
uint8_t BNO080::getAccelAccuracy()
{
return (accelAccuracy);
}
// linear acceleration, i.e. minus gravity
//Return the acceleration component
float BNO080::getLinAccelX()
{
float accel = qToFloat(rawLinAccelX, linear_accelerometer_Q1);
return (accel);
}
//Return the acceleration component
float BNO080::getLinAccelY()
{
float accel = qToFloat(rawLinAccelY, linear_accelerometer_Q1);
return (accel);
}
//Return the acceleration component
float BNO080::getLinAccelZ()
{
float accel = qToFloat(rawLinAccelZ, linear_accelerometer_Q1);
return (accel);
}
//Return the acceleration component
uint8_t BNO080::getLinAccelAccuracy()
{
return (accelLinAccuracy);
}
//Return the gyro component
float BNO080::getGyroX()
{
float gyro = qToFloat(rawGyroX, gyro_Q1);
return (gyro);
}
//Return the gyro component
float BNO080::getGyroY()
{
float gyro = qToFloat(rawGyroY, gyro_Q1);
return (gyro);
}
//Return the gyro component
float BNO080::getGyroZ()
{
float gyro = qToFloat(rawGyroZ, gyro_Q1);
return (gyro);
}
//Return the gyro component
uint8_t BNO080::getGyroAccuracy()
{
return (gyroAccuracy);
}
//Return the magnetometer component
float BNO080::getMagX()
{
float mag = qToFloat(rawMagX, magnetometer_Q1);
return (mag);
}
//Return the magnetometer component
float BNO080::getMagY()
{
float mag = qToFloat(rawMagY, magnetometer_Q1);
return (mag);
}
//Return the magnetometer component
float BNO080::getMagZ()
{
float mag = qToFloat(rawMagZ, magnetometer_Q1);
return (mag);
}
//Return the mag component
uint8_t BNO080::getMagAccuracy()
{
return (magAccuracy);
}
// Return the high refresh rate gyro component
float BNO080::getFastGyroX()
{
float gyro = qToFloat(rawFastGyroX, angular_velocity_Q1);
return (gyro);
}
// Return the high refresh rate gyro component
float BNO080::getFastGyroY()
{
float gyro = qToFloat(rawFastGyroY, angular_velocity_Q1);
return (gyro);
}
// Return the high refresh rate gyro component
float BNO080::getFastGyroZ()
{
float gyro = qToFloat(rawFastGyroZ, angular_velocity_Q1);
return (gyro);
}
//Return the step count
uint16_t BNO080::getStepCount()
{
return (stepCount);
}
//Return the stability classifier
uint8_t BNO080::getStabilityClassifier()
{
return (stabilityClassifier);
}
//Return the activity classifier
uint8_t BNO080::getActivityClassifier()
{
return (activityClassifier);
}
//Return the time stamp
uint32_t BNO080::getTimeStamp()
{
return (timeStamp);
}
//Return raw mems value for the accel
int16_t BNO080::getRawAccelX()
{
return (memsRawAccelX);
}
//Return raw mems value for the accel
int16_t BNO080::getRawAccelY()
{
return (memsRawAccelY);
}
//Return raw mems value for the accel
int16_t BNO080::getRawAccelZ()
{
return (memsRawAccelZ);
}
//Return raw mems value for the gyro
int16_t BNO080::getRawGyroX()
{
return (memsRawGyroX);
}
int16_t BNO080::getRawGyroY()
{
return (memsRawGyroY);
}
int16_t BNO080::getRawGyroZ()
{
return (memsRawGyroZ);
}
//Return raw mems value for the mag
int16_t BNO080::getRawMagX()
{
return (memsRawMagX);
}
int16_t BNO080::getRawMagY()
{
return (memsRawMagY);
}
int16_t BNO080::getRawMagZ()
{
return (memsRawMagZ);
}
//Given a record ID, read the Q1 value from the metaData record in the FRS (ya, it's complicated)
//Q1 is used for all sensor data calculations
int16_t BNO080::getQ1(uint16_t recordID)
{
//Q1 is always the lower 16 bits of word 7
uint16_t q = readFRSword(recordID, 7) & 0xFFFF; //Get word 7, lower 16 bits
return (q);
}
//Given a record ID, read the Q2 value from the metaData record in the FRS
//Q2 is used in sensor bias
int16_t BNO080::getQ2(uint16_t recordID)
{
//Q2 is always the upper 16 bits of word 7
uint16_t q = readFRSword(recordID, 7) >> 16; //Get word 7, upper 16 bits
return (q);
}
//Given a record ID, read the Q3 value from the metaData record in the FRS
//Q3 is used in sensor change sensitivity
int16_t BNO080::getQ3(uint16_t recordID)
{
//Q3 is always the upper 16 bits of word 8
uint16_t q = readFRSword(recordID, 8) >> 16; //Get word 8, upper 16 bits
return (q);
}
//Given a record ID, read the resolution value from the metaData record in the FRS for a given sensor
float BNO080::getResolution(uint16_t recordID)
{
//The resolution Q value are 'the same as those used in the sensor's input report'
//This should be Q1.
int16_t Q = getQ1(recordID);
//Resolution is always word 2
uint32_t value = readFRSword(recordID, 2); //Get word 2
float resolution = qToFloat(value, Q);
return (resolution);
}
//Given a record ID, read the range value from the metaData record in the FRS for a given sensor
float BNO080::getRange(uint16_t recordID)
{
//The resolution Q value are 'the same as those used in the sensor's input report'
//This should be Q1.
int16_t Q = getQ1(recordID);
//Range is always word 1
uint32_t value = readFRSword(recordID, 1); //Get word 1
float range = qToFloat(value, Q);
return (range);
}
//Given a record ID and a word number, look up the word data
//Helpful for pulling out a Q value, range, etc.
//Use readFRSdata for pulling out multi-word objects for a sensor (Vendor data for example)
uint32_t BNO080::readFRSword(uint16_t recordID, uint8_t wordNumber)
{
if (readFRSdata(recordID, wordNumber, 1) == true) //Get word number, just one word in length from FRS
return (metaData[0]); //Return this one word
return (0); //Error
}
//Ask the sensor for data from the Flash Record System
//See 6.3.6 page 40, FRS Read Request
void BNO080::frsReadRequest(uint16_t recordID, uint16_t readOffset, uint16_t blockSize)
{
shtpData[0] = SHTP_REPORT_FRS_READ_REQUEST; //FRS Read Request
shtpData[1] = 0; //Reserved
shtpData[2] = (readOffset >> 0) & 0xFF; //Read Offset LSB
shtpData[3] = (readOffset >> 8) & 0xFF; //Read Offset MSB
shtpData[4] = (recordID >> 0) & 0xFF; //FRS Type LSB
shtpData[5] = (recordID >> 8) & 0xFF; //FRS Type MSB
shtpData[6] = (blockSize >> 0) & 0xFF; //Block size LSB
shtpData[7] = (blockSize >> 8) & 0xFF; //Block size MSB
//Transmit packet on channel 2, 8 bytes
sendPacket(CHANNEL_CONTROL, 8);
}
//Given a sensor or record ID, and a given start/stop bytes, read the data from the Flash Record System (FRS) for this sensor
//Returns true if metaData array is loaded successfully
//Returns false if failure
bool BNO080::readFRSdata(uint16_t recordID, uint8_t startLocation, uint8_t wordsToRead)
{
uint8_t spot = 0;
//First we send a Flash Record System (FRS) request
frsReadRequest(recordID, startLocation, wordsToRead); //From startLocation of record, read a # of words
//Read bytes until FRS reports that the read is complete
while (1)
{
//Now we wait for response
while (1)
{
uint8_t counter = 0;
while (receivePacket() == false)
{
if (counter++ > 100)
return (false); //Give up
delay(1);
}
//We have the packet, inspect it for the right contents
//See page 40. Report ID should be 0xF3 and the FRS types should match the thing we requested
if (shtpData[0] == SHTP_REPORT_FRS_READ_RESPONSE)
if (((uint16_t)shtpData[13] << 8 | shtpData[12]) == recordID)
break; //This packet is one we are looking for
}
uint8_t dataLength = shtpData[1] >> 4;
uint8_t frsStatus = shtpData[1] & 0x0F;
uint32_t data0 = (uint32_t)shtpData[7] << 24 | (uint32_t)shtpData[6] << 16 | (uint32_t)shtpData[5] << 8 | (uint32_t)shtpData[4];
uint32_t data1 = (uint32_t)shtpData[11] << 24 | (uint32_t)shtpData[10] << 16 | (uint32_t)shtpData[9] << 8 | (uint32_t)shtpData[8];
//Record these words to the metaData array
if (dataLength > 0)
{
metaData[spot++] = data0;
}
if (dataLength > 1)
{
metaData[spot++] = data1;
}
if (spot >= MAX_METADATA_SIZE)
{
if (_printDebug == true)
_debugPort->println(F("metaData array over run. Returning."));
return (true); //We have run out of space in our array. Bail.
}
if (frsStatus == 3 || frsStatus == 6 || frsStatus == 7)
{
return (true); //FRS status is read completed! We're done!
}
}
}
//Send command to reset IC
//Read all advertisement packets from sensor
//The sensor has been seen to reset twice if we attempt too much too quickly.
//This seems to work reliably.
void BNO080::softReset(void)
{
shtpData[0] = 1; //Reset
//Attempt to start communication with sensor
sendPacket(CHANNEL_EXECUTABLE, 1); //Transmit packet on channel 1, 1 byte
//Read all incoming data and flush it
delay(50);
while (receivePacket() == true)
;
delay(50);
while (receivePacket() == true)
;
}
//Get the reason for the last reset
//1 = POR, 2 = Internal reset, 3 = Watchdog, 4 = External reset, 5 = Other
uint8_t BNO080::resetReason()
{
shtpData[0] = SHTP_REPORT_PRODUCT_ID_REQUEST; //Request the product ID and reset info
shtpData[1] = 0; //Reserved
//Transmit packet on channel 2, 2 bytes
sendPacket(CHANNEL_CONTROL, 2);
//Now we wait for response
if (receivePacket() == true)
{
if (shtpData[0] == SHTP_REPORT_PRODUCT_ID_RESPONSE)
{
return (shtpData[1]);
}
}
return (0);
}
//Given a register value and a Q point, convert to float
//See https://en.wikipedia.org/wiki/Q_(number_format)
float BNO080::qToFloat(int16_t fixedPointValue, uint8_t qPoint)
{
float qFloat = fixedPointValue;
qFloat *= pow(2, qPoint * -1);
return (qFloat);
}
//Sends the packet to enable the rotation vector
void BNO080::enableRotationVector(uint16_t timeBetweenReports)
{
setFeatureCommand(SENSOR_REPORTID_ROTATION_VECTOR, timeBetweenReports);
}
//Sends the packet to enable the ar/vr stabilized rotation vector
void BNO080::enableARVRStabilizedRotationVector(uint16_t timeBetweenReports)
{
setFeatureCommand(SENSOR_REPORTID_AR_VR_STABILIZED_ROTATION_VECTOR, timeBetweenReports);
}
//Sends the packet to enable the rotation vector
void BNO080::enableGameRotationVector(uint16_t timeBetweenReports)
{
setFeatureCommand(SENSOR_REPORTID_GAME_ROTATION_VECTOR, timeBetweenReports);
}
//Sends the packet to enable the ar/vr stabilized rotation vector
void BNO080::enableARVRStabilizedGameRotationVector(uint16_t timeBetweenReports)
{
setFeatureCommand(SENSOR_REPORTID_AR_VR_STABILIZED_GAME_ROTATION_VECTOR, timeBetweenReports);
}
//Sends the packet to enable the accelerometer
void BNO080::enableAccelerometer(uint16_t timeBetweenReports)
{
setFeatureCommand(SENSOR_REPORTID_ACCELEROMETER, timeBetweenReports);
}
//Sends the packet to enable the accelerometer
void BNO080::enableLinearAccelerometer(uint16_t timeBetweenReports)
{
setFeatureCommand(SENSOR_REPORTID_LINEAR_ACCELERATION, timeBetweenReports);
}
//Sends the packet to enable the gyro
void BNO080::enableGyro(uint16_t timeBetweenReports)
{
setFeatureCommand(SENSOR_REPORTID_GYROSCOPE, timeBetweenReports);
}
//Sends the packet to enable the magnetometer
void BNO080::enableMagnetometer(uint16_t timeBetweenReports)
{
setFeatureCommand(SENSOR_REPORTID_MAGNETIC_FIELD, timeBetweenReports);
}
//Sends the packet to enable the high refresh-rate gyro-integrated rotation vector
void BNO080::enableGyroIntegratedRotationVector(uint16_t timeBetweenReports)
{
setFeatureCommand(SENSOR_REPORTID_GYRO_INTEGRATED_ROTATION_VECTOR, timeBetweenReports);
}
//Sends the packet to enable the step counter
void BNO080::enableStepCounter(uint16_t timeBetweenReports)
{
setFeatureCommand(SENSOR_REPORTID_STEP_COUNTER, timeBetweenReports);
}
//Sends the packet to enable the Stability Classifier
void BNO080::enableStabilityClassifier(uint16_t timeBetweenReports)
{
setFeatureCommand(SENSOR_REPORTID_STABILITY_CLASSIFIER, timeBetweenReports);
}
//Sends the packet to enable the raw accel readings
//Note you must enable basic reporting on the sensor as well