-
Notifications
You must be signed in to change notification settings - Fork 0
/
mtdevice.py
executable file
·1925 lines (1801 loc) · 76.5 KB
/
mtdevice.py
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
#!/usr/bin/env python3
import serial
import struct
import sys
import getopt
import time
import datetime
import glob
import re
import pprint
from mtdef import MID, OutputMode, OutputSettings, MTException, Baudrates, \
XDIGroup, getMIDName, DeviceState, DeprecatedMID, MTErrorMessage, \
MTTimeoutException
################################################################
# MTDevice class
################################################################
class MTDevice(object):
"""XSens MT device communication object."""
def __init__(self, port, baudrate=115200, timeout=0.002, autoconf=True,
config_mode=False, verbose=False, initial_wait=0.1):
"""Open device."""
self.verbose = verbose
# serial interface to the device
try:
self.device = serial.Serial(port, baudrate, timeout=timeout,
writeTimeout=timeout)
except IOError:
# FIXME with pyserial3 we might need some specific flags
self.device = serial.Serial(port, baudrate, timeout=timeout,
writeTimeout=timeout, rtscts=True,
dsrdtr=True)
time.sleep(initial_wait) # open returns before device is ready
self.device.flushInput()
self.device.flushOutput()
# timeout for communication
self.timeout = 100*timeout
# state of the device
self.state = None
if autoconf:
self.auto_config_legacy()
else:
# mode parameter of the IMU
self.mode = None
# settings parameter of the IMU
self.settings = None
# length of the MTData message
self.length = None
# header of the MTData message
self.header = None
if config_mode:
self.GoToConfig()
############################################################
# Low-level communication
############################################################
def write_msg(self, mid, data=b''):
"""Low-level message sending function."""
length = len(data)
if length > 254:
lendat = b'\xFF' + struct.pack('!H', length)
else:
lendat = struct.pack('!B', length)
packet = b'\xFA\xFF' + struct.pack('!B', mid) + lendat + data
packet += struct.pack('!B', 0xFF & (-(sum(packet[1:]))))
msg = packet
start = time.time()
while ((time.time()-start) < self.timeout) and self.device.read():
pass
try:
self.device.write(msg)
except serial.serialutil.SerialTimeoutException:
raise MTTimeoutException("writing message")
if self.verbose:
print("MT: Write message id 0x%02X (%s) with %d data bytes: [%s]" %\
(mid, getMIDName(mid), length,
' '.join("%02X" % v for v in data)))
def waitfor(self, size=1):
"""Get a given amount of data."""
buf = bytearray()
for _ in range(100):
buf.extend(self.device.read(size-len(buf)))
if len(buf) == size:
return buf
if self.verbose:
print("waiting for %d bytes, got %d so far: [%s]" % \
(size, len(buf), ' '.join('%02X' % v for v in buf)))
raise MTTimeoutException("waiting for message")
def read_data_msg(self, buf=bytearray()):
"""Low-level MTData receiving function.
Take advantage of known message length.
"""
start = time.time()
if self.length <= 254:
totlength = 5 + self.length
else:
totlength = 7 + self.length
while (time.time()-start) < self.timeout:
buf.extend(self.waitfor(totlength - len(buf)))
preamble_ind = buf.find(self.header)
if preamble_ind == -1: # not found
# discard unexploitable data
if self.verbose:
sys.stderr.write("MT: discarding (no preamble).\n")
del buf[:-3]
continue
elif preamble_ind: # found but not at start
# discard leading bytes
if self.verbose:
sys.stderr.write("MT: discarding (before preamble).\n")
del buf[:preamble_ind]
# complete message for checksum
buf.extend(self.waitfor(totlength-len(buf)))
if 0xFF & sum(buf[1:]):
if self.verbose:
sys.stderr.write("MT: invalid checksum; discarding data and"
" waiting for next message.\n")
del buf[:buf.find(self.header)-2]
continue
data = str(buf[-self.length-1:-1])
del buf[:]
return data
else:
raise MTException("could not find MTData message.")
def read_msg(self):
"""Low-level message receiving function."""
start = time.time()
while (time.time()-start) < self.timeout:
# first part of preamble
if self.waitfor() != b'\xFA':
continue
# second part of preamble
if self.waitfor() != b'\xFF': # we assume no timeout anymore
continue
# read message id and length of message
mid, length = struct.unpack('!BB', self.waitfor(2))
if length == 255: # extended length
length, = struct.unpack('!H', self.waitfor(2))
# read contents and checksum
buf = self.waitfor(length+1)
checksum = buf[-1]
data = struct.unpack('!%dB' % length, buf[:-1])
# check message integrity
if 0xFF & sum(data, 0xFF+mid+length+checksum):
if self.verbose:
sys.stderr.write("invalid checksum; discarding data and "
"waiting for next message.\n")
continue
if self.verbose:
print("MT: Got message id 0x%02X (%s) with %d data bytes: [%s]"\
% (mid, getMIDName(mid), length,
' '.join("%02X" % v for v in data)))
if mid == MID.Error:
raise MTErrorMessage(data[0])
return (mid, buf[:-1])
else:
raise MTException("could not find message.")
def write_ack(self, mid, data=b'', n_retries=500):
"""Send a message and read confirmation."""
self.write_msg(mid, data)
for _ in range(n_retries):
mid_ack, data_ack = self.read_msg()
if mid_ack == (mid+1):
break
elif self.verbose:
print("ack (0x%02X) expected, got 0x%02X instead" % \
(mid+1, mid_ack))
else:
raise MTException("Ack (0x%02X) expected, MID 0x%02X received "
"instead (after %d retries)." % (mid+1, mid_ack,
n_retries))
return data_ack
def _ensure_config_state(self):
"""Switch device to config state if necessary."""
if self.state != DeviceState.Config:
self.GoToConfig()
def _ensure_measurement_state(self):
"""Switch device to measurement state if necessary."""
if self.state != DeviceState.Measurement:
self.GoToMeasurement()
############################################################
# High-level functions
############################################################
def Reset(self, go_to_config=False):
"""Reset MT device.
If go_to_config then send WakeUpAck in order to leave the device in
config mode.
"""
self.write_ack(MID.Reset)
if go_to_config:
time.sleep(0.01)
mid, _ = self.read_msg()
if mid == MID.WakeUp:
self.write_msg(MID.WakeUpAck)
self.state = DeviceState.Config
else:
self.state = DeviceState.Measurement
def GoToConfig(self):
"""Place MT device in configuration mode."""
self.write_ack(MID.GoToConfig)
self.state = DeviceState.Config
def GoToMeasurement(self):
"""Place MT device in measurement mode."""
self._ensure_config_state()
self.write_ack(MID.GoToMeasurement)
self.state = DeviceState.Measurement
def GetDeviceID(self):
"""Get the device identifier."""
self._ensure_config_state()
data = self.write_ack(MID.ReqDID)
deviceID, = struct.unpack('!I', data)
return deviceID
def GetProductCode(self):
"""Get the product code."""
self._ensure_config_state()
data = self.write_ack(MID.ReqProductCode)
return str(data).strip()
def GetFirmwareRev(self):
"""Get the firmware version."""
self._ensure_config_state()
data = self.write_ack(MID.ReqFWRev)
# XXX unpacking only 3 characters in accordance with the documentation
# but some devices send 11 bytes instead.
major, minor, revision = struct.unpack('!BBB', data[:3])
return (major, minor, revision)
def RunSelfTest(self):
"""Run the built-in self test."""
self._ensure_config_state()
data = self.write_ack(MID.RunSelfTest)
bit_names = ['accX', 'accY', 'accZ', 'gyrX', 'gyrY', 'gyrZ',
'magX', 'magY', 'magZ']
self_test_results = []
for i, name in enumerate(bit_names):
self_test_results.append((name, (data >> i) & 1))
return self_test_results
def GetBaudrate(self):
"""Get the current baudrate id of the device."""
self._ensure_config_state()
data = self.write_ack(MID.SetBaudrate)
return data[0]
def SetBaudrate(self, brid):
"""Set the baudrate of the device using the baudrate id."""
self._ensure_config_state()
self.write_ack(MID.SetBaudrate, (brid,))
def GetErrorMode(self):
"""Get the current error mode of the device."""
self._ensure_config_state()
data = self.write_ack(MID.SetErrorMode)
error_mode, = struct.unpack('!H', data)
return error_mode
def SetErrorMode(self, error_mode):
"""Set the error mode of the device.
The error mode defines the way the device deals with errors (expect
message errors):
0x0000: ignore any errors except message handling errors,
0x0001: in case of missing sampling instance: increase sample
counter and do not send error message,
0x0002: in case of missing sampling instance: increase sample
counter and send error message,
0x0003: in case of non-message handling error, an error message is
sent and the device will go into Config State.
"""
self._ensure_config_state()
data = struct.pack('!H', error_mode)
self.write_ack(MID.SetErrorMode, data)
def GetOptionFlags(self):
"""Get the option flags (MTi-1 series)."""
self._ensure_config_state()
data = self.write_ack(MID.SetOptionFlags)
flags, = struct.unpack('!I', data)
return flags
def SetOptionFlags(self, set_flags, clear_flags):
"""Set the option flags (MTi-1 series)."""
self._ensure_config_state()
data = struct.pack('!II', set_flags, clear_flags)
self.write_ack(MID.SetOptionFlags, data)
def GetLocationID(self):
"""Get the location ID of the device."""
self._ensure_config_state()
data = self.write_ack(MID.SetLocationID)
location_id, = struct.unpack('!H', data)
return location_id
def SetLocationID(self, location_id):
"""Set the location ID of the device (arbitrary)."""
self._ensure_config_state()
data = struct.pack('!H', location_id)
self.write_ack(MID.SetLocationID, data)
def RestoreFactoryDefaults(self):
"""Restore MT device configuration to factory defaults (soft version).
"""
self._ensure_config_state()
self.write_ack(MID.RestoreFactoryDef)
def GetTransmitDelay(self):
"""Get the transmission delay (only RS485)."""
self._ensure_config_state()
data = self.write_ack(MID.SetTransmitDelay)
transmit_delay, = struct.unpack('!H', data)
return transmit_delay
def SetTransmitDelay(self, transmit_delay):
"""Set the transmission delay (only RS485)."""
self._ensure_config_state()
data = struct.pack('!H', transmit_delay)
self.write_ack(MID.SetTransmitDelay, data)
def GetSyncSettings(self):
"""Get the synchronisation settings."""
self._ensure_config_state()
data = self.write_ack(MID.SetSyncSettings)
sync_settings = [struct.unpack('!BBBBHHHH', data[o:o+12])
for o in range(0, len(data), 12)]
return sync_settings
def SetSyncSettings(self, sync_settings):
"""Set the synchronisation settings (mark IV)"""
self._ensure_config_state()
data = b''.join(struct.pack('!BBBBHHHH', *sync_setting)
for sync_setting in sync_settings)
self.write_ack(MID.SetSyncSettings, data)
def GetConfiguration(self):
"""Ask for the current configuration of the MT device."""
self._ensure_config_state()
config = self.write_ack(MID.ReqConfiguration)
try:
masterID, period, skipfactor, _, _, _, date, time, num, deviceID,\
length, mode, settings =\
struct.unpack('!IHHHHI8s8s32x32xHIHHI8x', config)
except struct.error:
raise MTException("could not parse configuration.")
self.mode = mode
self.settings = settings
self.length = length
if self.length <= 254:
self.header = b'\xFA\xFF\x32' + struct.pack('!B', self.length)
else:
self.header = b'\xFA\xFF\x32\xFF' + struct.pack('!H', self.length)
conf = {'output-mode': mode,
'output-settings': settings,
'length': length,
'period': period,
'skipfactor': skipfactor,
'Master device ID': masterID,
'date': date,
'time': time,
'number of devices': num,
'device ID': deviceID}
return conf
def GetOutputConfiguration(self):
"""Get the output configuration of the device (mark IV)."""
self._ensure_config_state()
data = self.write_ack(MID.SetOutputConfiguration)
output_configuration = [struct.unpack('!HH', data[o:o+4])
for o in range(0, len(data), 4)]
return output_configuration
def SetOutputConfiguration(self, output_configuration):
"""Set the output configuration of the device (mark IV)."""
self._ensure_config_state()
data = b''.join(struct.pack('!HH', *output)
for output in output_configuration)
self.write_ack(MID.SetOutputConfiguration, data)
def GetStringOutputType(self):
"""Get the NMEA data output configuration."""
self._ensure_config_state()
data = self.write_ack(MID.SetStringOutputType)
string_output_type, = struct.unpack('!H', data)
return string_output_type
def SetStringOutputType(self, string_output_type):
"""Set the configuration of the NMEA data output."""
self._ensure_config_state()
data = struct.pack('!H', string_output_type)
self.write_ack(MID.SetStringOutputType, data)
def GetPeriod(self):
"""Get the sampling period."""
self._ensure_config_state()
data = self.write_ack(MID.SetPeriod)
period, = struct.unpack('!H', data)
return period
def SetPeriod(self, period):
"""Set the sampling period."""
self._ensure_config_state()
data = struct.pack('!H', period)
self.write_ack(MID.SetPeriod, data)
def GetAlignmentRotation(self, parameter):
"""Get the object alignment.
parameter indicates the desired alignment quaternion:
0 for sensor alignment (RotSensor),
1 for local alignment (RotLocal).
"""
self._ensure_config_state()
data = struct.pack('!B', parameter)
data = self.write_ack(MID.SetAlignmentRotation, data)
if len(data) == 16: # fix for older firmwares
q0, q1, q2, q3 = struct.unpack('!ffff', data)
return parameter, (q0, q1, q2, q3)
elif len(data) == 17:
param, q0, q1, q2, q3 = struct.unpack('!Bffff', data)
return param, (q0, q1, q2, q3)
else:
raise MTException('Could not parse ReqAlignmentRotationAck message:'
' wrong size of message (%d instead of either 16 '
'or 17).' % len(data))
def SetAlignmentRotation(self, parameter, quaternion):
"""Set the object alignment.
parameter indicates the desired alignment quaternion:
0 for sensor alignment (RotSensor),
1 for local alignment (RotLocal).
"""
self._ensure_config_state()
data = struct.pack('!Bffff', parameter, *quaternion)
self.write_ack(MID.SetAlignmentRotation, data)
def GetOutputMode(self):
"""Get current output mode."""
self._ensure_config_state()
data = self.write_ack(MID.SetOutputMode)
self.mode, = struct.unpack('!H', data)
return self.mode
def SetOutputMode(self, mode):
"""Select which information to output."""
self._ensure_config_state()
data = struct.pack('!H', mode)
self.write_ack(MID.SetOutputMode, data)
self.mode = mode
def GetExtOutputMode(self):
"""Get current extended output mode (for alternative UART)."""
self._ensure_config_state()
data = self.write_ack(MID.SetExtOutputMode)
ext_mode, = struct.unpack('!H', data)
return ext_mode
def SetExtOutputMode(self, ext_mode):
"""Set extended output mode (for alternative UART)."""
self._ensure_config_state()
data = struct.pack('!H', ext_mode)
self.write_ack(MID.SetExtOutputMode, data)
def GetOutputSettings(self):
"""Get current output mode."""
self._ensure_config_state()
data = self.write_ack(MID.SetOutputSettings)
self.settings, = struct.unpack('!I', data)
return self.settings
def SetOutputSettings(self, settings):
"""Select how to output the information."""
self._ensure_config_state()
data = struct.pack('!I', settings)
self.write_ack(MID.SetOutputSettings, data)
self.settings = settings
def SetOutputSkipFactor(self, skipfactor): # deprecated
"""Set the output skip factor."""
self._ensure_config_state()
data = struct.pack('!H', skipfactor)
self.write_ack(DeprecatedMID.SetOutputSkipFactor, data)
def ReqDataLength(self): # deprecated
"""Get data length for mark III devices."""
self._ensure_config_state()
try:
data = self.write_ack(DeprecatedMID.ReqDataLength)
except MTErrorMessage as e:
if e.code == 0x04:
sys.stderr.write("ReqDataLength message is deprecated and not "
"recognised by your device.")
return
raise e
self.length, = struct.unpack('!H', data)
if self.length <= 254:
self.header = b'\xFA\xFF\x32' + struct.pack('!B', self.length)
else:
self.header = b'\xFA\xFF\x32\xFF' + struct.pack('!H', self.length)
return self.length
def GetLatLonAlt(self):
"""Get the stored position of the device.
It is used internally for local magnetic declination and local gravity.
"""
self._ensure_config_state()
data = self.write_ack(MID.SetLatLonAlt)
if len(data) == 24:
lat, lon, alt = struct.unpack('!ddd', data)
elif len(data) == 12:
lat, lon, alt = struct.unpack('!fff', data)
else:
raise MTException('Could not parse ReqLatLonAltAck message: wrong'
'size of message.')
return (lat, lon, alt)
def SetLatLonAlt(self, lat, lon, alt):
"""Set the position of the device.
It is used internally for local magnetic declination and local gravity.
"""
self._ensure_config_state()
data = struct.pack('!ddd', lat, lon, alt)
self.write_ack(MID.SetLatLonAlt, data)
def GetAvailableScenarios(self):
"""Get the available XKF scenarios on the device."""
self._ensure_config_state()
data = self.write_ack(MID.ReqAvailableScenarios)
scenarios = []
try:
for i in range(len(data)/22):
scenario_type, version, label =\
struct.unpack('!BB20s', data[22*i:22*(i+1)])
scenarios.append((scenario_type, version, label.strip()))
# available XKF scenarios
self.scenarios = scenarios
except struct.error:
raise MTException("could not parse the available XKF scenarios.")
return scenarios
def GetCurrentScenario(self):
"""Get the ID of the currently used XKF scenario."""
self._ensure_config_state()
data = self.write_ack(MID.SetCurrentScenario)
_, self.scenario_id = struct.unpack('!BB', data) # version, id
return self.scenario_id
def SetCurrentScenario(self, scenario_id):
"""Sets the XKF scenario to use."""
self._ensure_config_state()
data = struct.pack('!BB', 0, scenario_id) # version, id
self.write_ack(MID.SetCurrentScenario, data)
def ResetOrientation(self, code):
"""Reset the orientation.
Code can take several values:
0x0000: store current settings (only in config mode),
0x0001: heading reset (NOT supported by MTi-G),
0x0003: object reset.
"""
data = struct.pack('!H', code)
self.write_ack(MID.ResetOrientation, data)
def SetNoRotation(self, duration):
"""Initiate the "no rotation" procedure to estimate gyro biases."""
self._ensure_measurement_state()
data = struct.pack('!H', duration)
self.write_ack(MID.SetNoRotation, data)
def GetUTCTime(self):
"""Get UTC time from device."""
self._ensure_config_state()
data = self.write_ack(MID.SetUTCTime)
ns, year, month, day, hour, minute, second, flag = \
struct.unpack('!IHBBBBBB', data)
return (ns, year, month, day, hour, minute, second, flag)
def SetUTCTime(self, ns, year, month, day, hour, minute, second, flag):
"""Set UTC time on the device."""
self._ensure_config_state()
data = struct.pack('!IHBBBBBB', ns, year, month, day, hour, minute,
second, flag) # no clue what setting flag can mean
self.write_ack(MID.SetUTCTime, data)
def AdjustUTCTime(self, ticks):
"""Adjust UTC Time of device using correction ticks (0.1 ms)."""
self._ensure_config_state()
data = struct.pack('!i', ticks)
self.write(MID.AdjustUTCTime, data) # no ack mentioned in the doc
############################################################
# High-level utility functions
############################################################
def configure_legacy(self, mode, settings, period=None, skipfactor=None):
"""Configure the mode and settings of the MT device in legacy mode."""
try:
# switch mark IV devices to legacy mode
self.SetOutputConfiguration([(0x0000, 0)])
except MTErrorMessage as e:
if e.code == 0x04:
# mark III device
pass
else:
raise
except MTException as e:
if self.verbose:
print("no ack received while switching from MTData2 to MTData.")
pass # no ack???
self.SetOutputMode(mode)
self.SetOutputSettings(settings)
if period is not None:
self.SetPeriod(period)
if skipfactor is not None:
self.SetOutputSkipFactor(skipfactor)
self.GetConfiguration()
def auto_config_legacy(self):
"""Read configuration from device in legacy mode."""
self.GetConfiguration()
return self.mode, self.settings, self.length
def read_measurement(self, mode=None, settings=None):
self._ensure_measurement_state()
# getting data
# data = self.read_data_msg()
mid, data = self.read_msg()
if mid == MID.MTData:
return self.parse_MTData(data, mode, settings)
elif mid == MID.MTData2:
return self.parse_MTData2(data)
else:
raise MTException("unknown data message: mid=0x%02X (%s)." %
(mid, getMIDName(mid)))
def parse_MTData2(self, data):
# Functions to parse each type of packet
def parse_temperature(data_id, content, ffmt):
o = {}
if (data_id & 0x00F0) == 0x10: # Temperature
o['Temp'], = struct.unpack('!'+ffmt, content)
else:
raise MTException("unknown packet: 0x%04X." % data_id)
return o
def parse_timestamp(data_id, content, ffmt):
o = {}
if (data_id & 0x00F0) == 0x10: # UTC Time
o['ns'], o['Year'], o['Month'], o['Day'], o['Hour'],\
o['Minute'], o['Second'], o['Flags'] =\
struct.unpack('!LHBBBBBB', content)
elif (data_id & 0x00F0) == 0x20: # Packet Counter
o['PacketCounter'], = struct.unpack('!H', content)
elif (data_id & 0x00F0) == 0x30: # Integer Time of Week
o['TimeOfWeek'], = struct.unpack('!L', content)
elif (data_id & 0x00F0) == 0x40: # GPS Age # deprecated
o['gpsAge'], = struct.unpack('!B', content)
elif (data_id & 0x00F0) == 0x50: # Pressure Age # deprecated
o['pressureAge'], = struct.unpack('!B', content)
elif (data_id & 0x00F0) == 0x60: # Sample Time Fine
o['SampleTimeFine'], = struct.unpack('!L', content)
elif (data_id & 0x00F0) == 0x70: # Sample Time Coarse
o['SampleTimeCoarse'], = struct.unpack('!L', content)
elif (data_id & 0x00F0) == 0x80: # Frame Range
o['startFrame'], o['endFrame'] = struct.unpack('!HH', content)
else:
raise MTException("unknown packet: 0x%04X." % data_id)
return o
def parse_orientation_data(data_id, content, ffmt):
o = {}
if (data_id & 0x000C) == 0x00: # ENU
o['frame'] = 'ENU'
elif (data_id & 0x000C) == 0x04: # NED
o['frame'] = 'NED'
elif (data_id & 0x000C) == 0x08: # NWU
o['frame'] = 'NWU'
if (data_id & 0x00F0) == 0x10: # Quaternion
o['Q0'], o['Q1'], o['Q2'], o['Q3'] = struct.unpack('!'+4*ffmt,
content)
elif (data_id & 0x00F0) == 0x20: # Rotation Matrix
o['a'], o['b'], o['c'], o['d'], o['e'], o['f'], o['g'], o['h'],\
o['i'] = struct.unpack('!'+9*ffmt, content)
elif (data_id & 0x00F0) == 0x30: # Euler Angles
o['Roll'], o['Pitch'], o['Yaw'] = struct.unpack('!'+3*ffmt,
content)
else:
raise MTException("unknown packet: 0x%04X." % data_id)
return o
def parse_pressure(data_id, content, ffmt):
o = {}
if (data_id & 0x00F0) == 0x10: # Baro pressure
o['Pressure'], = struct.unpack('!L', content)
else:
raise MTException("unknown packet: 0x%04X." % data_id)
return o
def parse_acceleration(data_id, content, ffmt):
o = {}
if (data_id & 0x000C) == 0x00: # ENU
o['frame'] = 'ENU'
elif (data_id & 0x000C) == 0x04: # NED
o['frame'] = 'NED'
elif (data_id & 0x000C) == 0x08: # NWU
o['frame'] = 'NWU'
if (data_id & 0x00F0) == 0x10: # Delta V
o['Delta v.x'], o['Delta v.y'], o['Delta v.z'] = \
struct.unpack('!'+3*ffmt, content)
elif (data_id & 0x00F0) == 0x20: # Acceleration
o['accX'], o['accY'], o['accZ'] = \
struct.unpack('!'+3*ffmt, content)
elif (data_id & 0x00F0) == 0x30: # Free Acceleration
o['freeAccX'], o['freeAccY'], o['freeAccZ'] = \
struct.unpack('!'+3*ffmt, content)
elif (data_id & 0x00F0) == 0x40: # AccelerationHR
o['accX'], o['accY'], o['accZ'] = \
struct.unpack('!'+3*ffmt, content)
else:
raise MTException("unknown packet: 0x%04X." % data_id)
return o
def parse_position(data_id, content, ffmt):
o = {}
if (data_id & 0x000C) == 0x00: # ENU
o['frame'] = 'ENU'
elif (data_id & 0x000C) == 0x04: # NED
o['frame'] = 'NED'
elif (data_id & 0x000C) == 0x08: # NWU
o['frame'] = 'NWU'
if (data_id & 0x00F0) == 0x10: # Altitude MSL # deprecated
o['altMsl'], = struct.unpack('!'+ffmt, content)
elif (data_id & 0x00F0) == 0x20: # Altitude Ellipsoid
o['altEllipsoid'], = struct.unpack('!'+ffmt, content)
elif (data_id & 0x00F0) == 0x30: # Position ECEF
o['ecefX'], o['ecefY'], o['ecefZ'] = \
struct.unpack('!'+3*ffmt, content)
elif (data_id & 0x00F0) == 0x40: # LatLon
o['lat'], o['lon'] = struct.unpack('!'+2*ffmt, content)
else:
raise MTException("unknown packet: 0x%04X." % data_id)
return o
def parse_GNSS(data_id, content, ffmt):
o = {}
if (data_id & 0x00F0) == 0x10: # GNSS PVT data
o['itow'], o['year'], o['month'], o['day'], o['hour'],\
o['min'], o['sec'], o['valid'], o['tAcc'], o['nano'],\
o['fixtype'], o['flags'], o['numSV'], o['lon'], o['lat'],\
o['height'], o['hMSL'], o['hAcc'], o['vAcc'], o['velN'],\
o['velE'], o['velD'], o['gSpeed'], o['headMot'], o['sAcc'],\
o['headAcc'], o['headVeh'], o['gdop'], o['pdop'],\
o['tdop'], o['vdop'], o['hdop'], o['ndop'], o['edop'] = \
struct.unpack('!IHBBBBBBIiBBBxiiiiIIiiiiiIIiHHHHHHH',
content)
# scaling correction
o['lon'] *= 1e-7
o['lat'] *= 1e-7
o['headMot'] *= 1e-5
o['headVeh'] *= 1e-5
o['gdop'] *= 0.01
o['pdop'] *= 0.01
o['tdop'] *= 0.01
o['vdop'] *= 0.01
o['hdop'] *= 0.01
o['ndop'] *= 0.01
o['edop'] *= 0.01
elif (data_id & 0x00F0) == 0x20: # GNSS satellites info
o['iTOW'], o['numSvs'] = struct.unpack('!LBxxx', content[:8])
svs = []
ch = {}
for i in range(o['numSvs']):
ch['gnssId'], ch['svId'], ch['cno'], ch['flags'] = \
struct.unpack('!BBBB', content[8+4*i:12+4*i])
svs.append(ch)
o['svs'] = svs
else:
raise MTException("unknown packet: 0x%04X." % data_id)
return o
def parse_angular_velocity(data_id, content, ffmt):
o = {}
if (data_id & 0x000C) == 0x00: # ENU
o['frame'] = 'ENU'
elif (data_id & 0x000C) == 0x04: # NED
o['frame'] = 'NED'
elif (data_id & 0x000C) == 0x08: # NWU
o['frame'] = 'NWU'
if (data_id & 0x00F0) == 0x20: # Rate of Turn
o['gyrX'], o['gyrY'], o['gyrZ'] = \
struct.unpack('!'+3*ffmt, content)
elif (data_id & 0x00F0) == 0x30: # Delta Q
o['Delta q0'], o['Delta q1'], o['Delta q2'], o['Delta q3'] = \
struct.unpack('!'+4*ffmt, content)
elif (data_id & 0x00F0) == 0x40: # RateOfTurnHR
o['gyrX'], o['gyrY'], o['gyrZ'] = \
struct.unpack('!'+3*ffmt, content)
else:
raise MTException("unknown packet: 0x%04X." % data_id)
return o
def parse_GPS(data_id, content, ffmt):
o = {}
if (data_id & 0x00F0) == 0x30: # DOP
o['iTOW'], g, p, t, v, h, n, e = \
struct.unpack('!LHHHHHHH', content)
o['gDOP'], o['pDOP'], o['tDOP'], o['vDOP'], o['hDOP'], \
o['nDOP'], o['eDOP'] = 0.01*g, 0.01*p, 0.01*t, \
0.01*v, 0.01*h, 0.01*n, 0.01*e
elif (data_id & 0x00F0) == 0x40: # SOL
o['iTOW'], o['fTOW'], o['Week'], o['gpsFix'], o['Flags'], \
o['ecefX'], o['ecefY'], o['ecefZ'], o['pAcc'], \
o['ecefVX'], o['ecefVY'], o['ecefVZ'], o['sAcc'], \
o['pDOP'], o['numSV'] = \
struct.unpack('!LlhBBlllLlllLHxBx', content)
# scaling correction
o['pDOP'] *= 0.01
elif (data_id & 0x00F0) == 0x80: # Time UTC
o['iTOW'], o['tAcc'], o['nano'], o['year'], o['month'], \
o['day'], o['hour'], o['min'], o['sec'], o['valid'] = \
struct.unpack('!LLlHBBBBBB', content)
elif (data_id & 0x00F0) == 0xA0: # SV Info
o['iTOW'], o['numCh'] = struct.unpack('!LBxxx', content[:8])
channels = []
ch = {}
for i in range(o['numCh']):
ch['chn'], ch['svid'], ch['flags'], ch['quality'], \
ch['cno'], ch['elev'], ch['azim'], ch['prRes'] = \
struct.unpack('!BBBBBbhl', content[8+12*i:20+12*i])
channels.append(ch)
o['channels'] = channels
else:
raise MTException("unknown packet: 0x%04X." % data_id)
return o
def parse_SCR(data_id, content, ffmt):
o = {}
if (data_id & 0x00F0) == 0x10: # ACC+GYR+MAG+Temperature
o['accX'], o['accY'], o['accZ'], o['gyrX'], o['gyrY'], \
o['gyrZ'], o['magX'], o['magY'], o['magZ'], o['Temp'] = \
struct.unpack("!9Hh", content)
elif (data_id & 0x00F0) == 0x20: # Gyro Temperature
o['tempGyrX'], o['tempGyrY'], o['tempGyrZ'] = \
struct.unpack("!hhh", content)
else:
raise MTException("unknown packet: 0x%04X." % data_id)
return o
def parse_analog_in(data_id, content, ffmt): # deprecated
o = {}
if (data_id & 0x00F0) == 0x10: # Analog In 1
o['analogIn1'], = struct.unpack("!H", content)
elif (data_id & 0x00F0) == 0x20: # Analog In 2
o['analogIn2'], = struct.unpack("!H", content)
else:
raise MTException("unknown packet: 0x%04X." % data_id)
return o
def parse_magnetic(data_id, content, ffmt):
o = {}
if (data_id & 0x000C) == 0x00: # ENU
o['frame'] = 'ENU'
elif (data_id & 0x000C) == 0x04: # NED
o['frame'] = 'NED'
elif (data_id & 0x000C) == 0x08: # NWU
o['frame'] = 'NWU'
if (data_id & 0x00F0) == 0x20: # Magnetic Field
o['magX'], o['magY'], o['magZ'] = \
struct.unpack("!3"+ffmt, content)
else:
raise MTException("unknown packet: 0x%04X." % data_id)
return o
def parse_velocity(data_id, content, ffmt):
o = {}
if (data_id & 0x000C) == 0x00: # ENU
o['frame'] = 'ENU'
elif (data_id & 0x000C) == 0x04: # NED
o['frame'] = 'NED'
elif (data_id & 0x000C) == 0x08: # NWU
o['frame'] = 'NWU'
if (data_id & 0x00F0) == 0x10: # Velocity XYZ
o['velX'], o['velY'], o['velZ'] = \
struct.unpack("!3"+ffmt, content)
else:
raise MTException("unknown packet: 0x%04X." % data_id)
return o
def parse_status(data_id, content, ffmt):
o = {}
if (data_id & 0x00F0) == 0x10: # Status Byte
o['StatusByte'], = struct.unpack("!B", content)
elif (data_id & 0x00F0) == 0x20: # Status Word
o['StatusWord'], = struct.unpack("!L", content)
elif (data_id & 0x00F0) == 0x40: # RSSI # deprecated
o['RSSI'], = struct.unpack("!b", content)
else:
raise MTException("unknown packet: 0x%04X." % data_id)
return o
# data object
output = {}
while data:
try:
data_id, size = struct.unpack('!HB', data[:3])
if (data_id & 0x0003) == 0x3:
float_format = 'd'
elif (data_id & 0x0003) == 0x0:
float_format = 'f'
else:
raise MTException("fixed point precision not supported.")
content = data[3:3+size]
data = data[3+size:]
group = data_id & 0xF800
ffmt = float_format
if group == XDIGroup.Temperature:
output.setdefault('Temperature', {}).update(
parse_temperature(data_id, content, ffmt))
elif group == XDIGroup.Timestamp:
output.setdefault('Timestamp', {}).update(
parse_timestamp(data_id, content, ffmt))
elif group == XDIGroup.OrientationData:
output.setdefault('Orientation Data', {}).update(
parse_orientation_data(data_id, content, ffmt))
elif group == XDIGroup.Pressure:
output.setdefault('Pressure', {}).update(
parse_pressure(data_id, content, ffmt))
elif group == XDIGroup.Acceleration:
output.setdefault('Acceleration', {}).update(
parse_acceleration(data_id, content, ffmt))
elif group == XDIGroup.Position:
output.setdefault('Position', {}).update(
parse_position(data_id, content, ffmt))
elif group == XDIGroup.GNSS:
output.setdefault('GNSS', {}).update(
parse_GNSS(data_id, content, ffmt))
elif group == XDIGroup.AngularVelocity:
output.setdefault('Angular Velocity', {}).update(
parse_angular_velocity(data_id, content, ffmt))
elif group == XDIGroup.GPS:
output.setdefault('GPS', {}).update(
parse_GPS(data_id, content, ffmt))
elif group == XDIGroup.SensorComponentReadout:
output.setdefault('SCR', {}).update(
parse_SCR(data_id, content, ffmt))
elif group == XDIGroup.AnalogIn: # deprecated
output.setdefault('Analog In', {}).update(
parse_analog_in(data_id, content, ffmt))
elif group == XDIGroup.Magnetic:
output.setdefault('Magnetic', {}).update(
parse_magnetic(data_id, content, ffmt))
elif group == XDIGroup.Velocity:
output.setdefault('Velocity', {}).update(
parse_velocity(data_id, content, ffmt))
elif group == XDIGroup.Status:
output.setdefault('Status', {}).update(
parse_status(data_id, content, ffmt))
else:
raise MTException("unknown XDI group: 0x%04X." % group)
except struct.error:
raise MTException("couldn't parse MTData2 message.")
return output
def parse_MTData(self, data, mode=None, settings=None):
"""Read and parse a legacy measurement packet."""
# getting mode
if mode is None:
mode = self.mode
if settings is None:
settings = self.settings
# data object
output = {}
try:
# raw IMU first
if mode & OutputMode.RAW:
o = {}
o['accX'], o['accY'], o['accZ'], o['gyrX'], o['gyrY'], \
o['gyrZ'], o['magX'], o['magY'], o['magZ'], o['temp'] =\
struct.unpack('!10H', data[:20])
data = data[20:]
output['RAW'] = o
# raw GPS second
if mode & OutputMode.RAWGPS:
o = {}
o['Press'], o['bPrs'], o['ITOW'], o['LAT'], o['LON'], o['ALT'],\
o['VEL_N'], o['VEL_E'], o['VEL_D'], o['Hacc'], o['Vacc'],\