mtdevice.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 import serial
3 import struct
4 import sys
5 import getopt
6 import time
7 import datetime
8 import glob
9 import re
10 import pprint
11 
12 from mtdef import MID, OutputMode, OutputSettings, MTException, Baudrates, \
13  XDIGroup, getMIDName, DeviceState, DeprecatedMID, MTErrorMessage, \
14  MTTimeoutException
15 
16 
17 ################################################################
18 # MTDevice class
19 ################################################################
20 class MTDevice(object):
21  """XSens MT device communication object."""
22 
23  def __init__(self, port, baudrate=115200, timeout=0.002, autoconf=True,
24  config_mode=False, verbose=False, initial_wait=0.1):
25  """Open device."""
26  self.verbose = verbose
27  # serial interface to the device
28  try:
29  self.device = serial.Serial(port, baudrate, timeout=timeout,
30  writeTimeout=timeout)
31  except IOError:
32  # FIXME with pyserial3 we might need some specific flags
33  self.device = serial.Serial(port, baudrate, timeout=timeout,
34  writeTimeout=timeout, rtscts=True,
35  dsrdtr=True)
36  time.sleep(initial_wait) # open returns before device is ready
37  self.device.flushInput()
38  self.device.flushOutput()
39  # timeout for communication
40  self.timeout = 100*timeout
41  # state of the device
42  self.state = None
43  if autoconf:
44  self.auto_config_legacy()
45  else:
46  # mode parameter of the IMU
47  self.mode = None
48  # settings parameter of the IMU
49  self.settings = None
50  # length of the MTData message
51  self.length = None
52  # header of the MTData message
53  self.header = None
54  if config_mode:
55  self.GoToConfig()
56 
57  ############################################################
58  # Low-level communication
59  ############################################################
60  def write_msg(self, mid, data=b''):
61  """Low-level message sending function."""
62  length = len(data)
63  if length > 254:
64  lendat = b'\xFF' + struct.pack('!H', length)
65  else:
66  lendat = struct.pack('!B', length)
67  packet = b'\xFA\xFF' + struct.pack('!B', mid) + lendat + data
68  packet += struct.pack('!B', 0xFF & (-(sum(map(ord, packet[1:])))))
69  msg = packet
70  start = time.time()
71  while ((time.time()-start) < self.timeout) and self.device.read():
72  pass
73  try:
74  self.device.write(msg)
75  except serial.serialutil.SerialTimeoutException:
76  raise MTTimeoutException("writing message")
77  if self.verbose:
78  print "MT: Write message id 0x%02X (%s) with %d data bytes: [%s]" %\
79  (mid, getMIDName(mid), length,
80  ' '.join("%02X" % ord(v) for v in data))
81 
82  def waitfor(self, size=1):
83  """Get a given amount of data."""
84  buf = bytearray()
85  for _ in range(100):
86  buf.extend(self.device.read(size-len(buf)))
87  if len(buf) == size:
88  return buf
89  if self.verbose:
90  print "waiting for %d bytes, got %d so far: [%s]" % \
91  (size, len(buf), ' '.join('%02X' % v for v in buf))
92  raise MTTimeoutException("waiting for message")
93 
94  def read_data_msg(self, buf=bytearray()):
95  """Low-level MTData receiving function.
96  Take advantage of known message length.
97  """
98  start = time.time()
99  if self.length <= 254:
100  totlength = 5 + self.length
101  else:
102  totlength = 7 + self.length
103  while (time.time()-start) < self.timeout:
104  buf.extend(self.waitfor(totlength - len(buf)))
105  preamble_ind = buf.find(self.header)
106  if preamble_ind == -1: # not found
107  # discard unexploitable data
108  if self.verbose:
109  sys.stderr.write("MT: discarding (no preamble).\n")
110  del buf[:-3]
111  continue
112  elif preamble_ind: # found but not at start
113  # discard leading bytes
114  if self.verbose:
115  sys.stderr.write("MT: discarding (before preamble).\n")
116  del buf[:preamble_ind]
117  # complete message for checksum
118  buf.extend(self.waitfor(totlength-len(buf)))
119  if 0xFF & sum(buf[1:]):
120  if self.verbose:
121  sys.stderr.write("MT: invalid checksum; discarding data and"
122  " waiting for next message.\n")
123  del buf[:buf.find(self.header)-2]
124  continue
125  data = str(buf[-self.length-1:-1])
126  del buf[:]
127  return data
128  else:
129  raise MTException("could not find MTData message.")
130 
131  def read_msg(self):
132  """Low-level message receiving function."""
133  start = time.time()
134  while (time.time()-start) < self.timeout:
135  # first part of preamble
136  if ord(self.waitfor()) != 0xFA:
137  continue
138  # second part of preamble
139  if ord(self.waitfor()) != 0xFF: # we assume no timeout anymore
140  continue
141  # read message id and length of message
142  mid, length = struct.unpack('!BB', self.waitfor(2))
143  if length == 255: # extended length
144  length, = struct.unpack('!H', self.waitfor(2))
145  # read contents and checksum
146  buf = self.waitfor(length+1)
147  checksum = buf[-1]
148  data = struct.unpack('!%dB' % length, buf[:-1])
149  # check message integrity
150  if 0xFF & sum(data, 0xFF+mid+length+checksum):
151  if self.verbose:
152  sys.stderr.write("invalid checksum; discarding data and "
153  "waiting for next message.\n")
154  continue
155  if self.verbose:
156  print "MT: Got message id 0x%02X (%s) with %d data bytes: [%s]"\
157  % (mid, getMIDName(mid), length,
158  ' '.join("%02X" % v for v in data))
159  if mid == MID.Error:
160  raise MTErrorMessage(data[0])
161  return (mid, buf[:-1])
162  else:
163  raise MTException("could not find message.")
164 
165  def write_ack(self, mid, data=b'', n_retries=500):
166  """Send a message and read confirmation."""
167  self.write_msg(mid, data)
168  for _ in range(n_retries):
169  mid_ack, data_ack = self.read_msg()
170  if mid_ack == (mid+1):
171  break
172  elif self.verbose:
173  print "ack (0x%02X) expected, got 0x%02X instead" % \
174  (mid+1, mid_ack)
175  else:
176  raise MTException("Ack (0x%02X) expected, MID 0x%02X received "
177  "instead (after %d retries)." % (mid+1, mid_ack,
178  n_retries))
179  return data_ack
180 
182  """Switch device to config state if necessary."""
183  if self.state != DeviceState.Config:
184  self.GoToConfig()
185 
187  """Switch device to measurement state if necessary."""
188  if self.state != DeviceState.Measurement:
189  self.GoToMeasurement()
190 
191  ############################################################
192  # High-level functions
193  ############################################################
194  def Reset(self, go_to_config=False):
195  """Reset MT device.
196 
197  If go_to_config then send WakeUpAck in order to leave the device in
198  config mode.
199  """
200  self.write_ack(MID.Reset)
201  if go_to_config:
202  time.sleep(0.01)
203  mid, _ = self.read_msg()
204  if mid == MID.WakeUp:
205  self.write_msg(MID.WakeUpAck)
206  self.state = DeviceState.Config
207  else:
208  self.state = DeviceState.Measurement
209 
210  def GoToConfig(self):
211  """Place MT device in configuration mode."""
212  self.write_ack(MID.GoToConfig)
213  self.state = DeviceState.Config
214 
215  def GoToMeasurement(self):
216  """Place MT device in measurement mode."""
217  self._ensure_config_state()
218  self.write_ack(MID.GoToMeasurement)
219  self.state = DeviceState.Measurement
220 
221  def GetDeviceID(self):
222  """Get the device identifier."""
223  self._ensure_config_state()
224  data = self.write_ack(MID.ReqDID)
225  deviceID, = struct.unpack('!I', data)
226  return deviceID
227 
228  def GetProductCode(self):
229  """Get the product code."""
230  self._ensure_config_state()
231  data = self.write_ack(MID.ReqProductCode)
232  return str(data).strip()
233 
234  def GetFirmwareRev(self):
235  """Get the firmware version."""
236  self._ensure_config_state()
237  data = self.write_ack(MID.ReqFWRev)
238  # XXX unpacking only 3 characters in accordance with the documentation
239  # but some devices send 11 bytes instead.
240  major, minor, revision = struct.unpack('!BBB', data[:3])
241  return (major, minor, revision)
242 
243  def RunSelfTest(self):
244  """Run the built-in self test."""
245  self._ensure_config_state()
246  data = self.write_ack(MID.RunSelfTest)
247  bit_names = ['accX', 'accY', 'accZ', 'gyrX', 'gyrY', 'gyrZ',
248  'magX', 'magY', 'magZ']
249  self_test_results = []
250  for i, name in enumerate(bit_names):
251  self_test_results.append((name, (data >> i) & 1))
252  return self_test_results
253 
254  def GetBaudrate(self):
255  """Get the current baudrate id of the device."""
256  self._ensure_config_state()
257  data = self.write_ack(MID.SetBaudrate)
258  return data[0]
259 
260  def SetBaudrate(self, brid):
261  """Set the baudrate of the device using the baudrate id."""
262  self._ensure_config_state()
263  self.write_ack(MID.SetBaudrate, (brid,))
264 
265  def GetErrorMode(self):
266  """Get the current error mode of the device."""
267  self._ensure_config_state()
268  data = self.write_ack(MID.SetErrorMode)
269  error_mode, = struct.unpack('!H', data)
270  return error_mode
271 
272  def SetErrorMode(self, error_mode):
273  """Set the error mode of the device.
274 
275  The error mode defines the way the device deals with errors (expect
276  message errors):
277  0x0000: ignore any errors except message handling errors,
278  0x0001: in case of missing sampling instance: increase sample
279  counter and do not send error message,
280  0x0002: in case of missing sampling instance: increase sample
281  counter and send error message,
282  0x0003: in case of non-message handling error, an error message is
283  sent and the device will go into Config State.
284  """
285  self._ensure_config_state()
286  data = struct.pack('!H', error_mode)
287  self.write_ack(MID.SetErrorMode, data)
288 
289  def GetOptionFlags(self):
290  """Get the option flags (MTi-1 series)."""
291  self._ensure_config_state()
292  data = self.write_ack(MID.SetOptionFlags)
293  flags, = struct.unpack('!I', data)
294  return flags
295 
296  def SetOptionFlags(self, set_flags, clear_flags):
297  """Set the option flags (MTi-1 series)."""
298  self._ensure_config_state()
299  data = struct.pack('!II', set_flags, clear_flags)
300  self.write_ack(MID.SetOptionFlags, data)
301 
302  def GetLocationID(self):
303  """Get the location ID of the device."""
304  self._ensure_config_state()
305  data = self.write_ack(MID.SetLocationID)
306  location_id, = struct.unpack('!H', data)
307  return location_id
308 
309  def SetLocationID(self, location_id):
310  """Set the location ID of the device (arbitrary)."""
311  self._ensure_config_state()
312  data = struct.pack('!H', location_id)
313  self.write_ack(MID.SetLocationID, data)
314 
316  """Restore MT device configuration to factory defaults (soft version).
317  """
318  self._ensure_config_state()
319  self.write_ack(MID.RestoreFactoryDef)
320 
321  def GetTransmitDelay(self):
322  """Get the transmission delay (only RS485)."""
323  self._ensure_config_state()
324  data = self.write_ack(MID.SetTransmitDelay)
325  transmit_delay, = struct.unpack('!H', data)
326  return transmit_delay
327 
328  def SetTransmitDelay(self, transmit_delay):
329  """Set the transmission delay (only RS485)."""
330  self._ensure_config_state()
331  data = struct.pack('!H', transmit_delay)
332  self.write_ack(MID.SetTransmitDelay, data)
333 
334  def GetSyncSettings(self):
335  """Get the synchronisation settings."""
336  self._ensure_config_state()
337  data = self.write_ack(MID.SetSyncSettings)
338  sync_settings = [struct.unpack('!BBBBHHHH', data[o:o+12])
339  for o in range(0, len(data), 12)]
340  return sync_settings
341 
342  def SetSyncSettings(self, sync_settings):
343  """Set the synchronisation settings (mark IV)"""
344  self._ensure_config_state()
345  data = b''.join(struct.pack('!BBBBHHHH', *sync_setting)
346  for sync_setting in sync_settings)
347  self.write_ack(MID.SetSyncSettings, data)
348 
349  def GetConfiguration(self):
350  """Ask for the current configuration of the MT device."""
351  self._ensure_config_state()
352  config = self.write_ack(MID.ReqConfiguration)
353  try:
354  masterID, period, skipfactor, _, _, _, date, time, num, deviceID,\
355  length, mode, settings =\
356  struct.unpack('!IHHHHI8s8s32x32xHIHHI8x', config)
357  except struct.error:
358  raise MTException("could not parse configuration.")
359  self.mode = mode
360  self.settings = settings
361  self.length = length
362  if self.length <= 254:
363  self.header = b'\xFA\xFF\x32' + struct.pack('!B', self.length)
364  else:
365  self.header = b'\xFA\xFF\x32\xFF' + struct.pack('!H', self.length)
366  conf = {'output-mode': mode,
367  'output-settings': settings,
368  'length': length,
369  'period': period,
370  'skipfactor': skipfactor,
371  'Master device ID': masterID,
372  'date': date,
373  'time': time,
374  'number of devices': num,
375  'device ID': deviceID}
376  return conf
377 
379  """Get the output configuration of the device (mark IV)."""
380  self._ensure_config_state()
381  data = self.write_ack(MID.SetOutputConfiguration)
382  output_configuration = [struct.unpack('!HH', data[o:o+4])
383  for o in range(0, len(data), 4)]
384  return output_configuration
385 
386  def SetOutputConfiguration(self, output_configuration):
387  """Set the output configuration of the device (mark IV)."""
388  self._ensure_config_state()
389  data = b''.join(struct.pack('!HH', *output)
390  for output in output_configuration)
391  self.write_ack(MID.SetOutputConfiguration, data)
392 
394  """Get the NMEA data output configuration."""
395  self._ensure_config_state()
396  data = self.write_ack(MID.SetStringOutputType)
397  string_output_type, = struct.unpack('!H', data)
398  return string_output_type
399 
400  def SetStringOutputType(self, string_output_type):
401  """Set the configuration of the NMEA data output."""
402  self._ensure_config_state()
403  data = struct.pack('!H', string_output_type)
404  self.write_ack(MID.SetStringOutputType, data)
405 
406  def GetPeriod(self):
407  """Get the sampling period."""
408  self._ensure_config_state()
409  data = self.write_ack(MID.SetPeriod)
410  period, = struct.unpack('!H', data)
411  return period
412 
413  def SetPeriod(self, period):
414  """Set the sampling period."""
415  self._ensure_config_state()
416  data = struct.pack('!H', period)
417  self.write_ack(MID.SetPeriod, data)
418 
419  def GetAlignmentRotation(self, parameter):
420  """Get the object alignment.
421 
422  parameter indicates the desired alignment quaternion:
423  0 for sensor alignment (RotSensor),
424  1 for local alignment (RotLocal).
425  """
426  self._ensure_config_state()
427  data = struct.pack('!B', parameter)
428  data = self.write_ack(MID.SetAlignmentRotation, data)
429  if len(data) == 16: # fix for older firmwares
430  q0, q1, q2, q3 = struct.unpack('!ffff', data)
431  return parameter, (q0, q1, q2, q3)
432  elif len(data) == 17:
433  param, q0, q1, q2, q3 = struct.unpack('!Bffff', data)
434  return param, (q0, q1, q2, q3)
435  else:
436  raise MTException('Could not parse ReqAlignmentRotationAck message:'
437  ' wrong size of message (%d instead of either 16 '
438  'or 17).' % len(data))
439 
440  def SetAlignmentRotation(self, parameter, quaternion):
441  """Set the object alignment.
442 
443  parameter indicates the desired alignment quaternion:
444  0 for sensor alignment (RotSensor),
445  1 for local alignment (RotLocal).
446  """
447  self._ensure_config_state()
448  data = struct.pack('!Bffff', parameter, *quaternion)
449  self.write_ack(MID.SetAlignmentRotation, data)
450 
451  def GetOutputMode(self):
452  """Get current output mode."""
453  self._ensure_config_state()
454  data = self.write_ack(MID.SetOutputMode)
455  self.mode, = struct.unpack('!H', data)
456  return self.mode
457 
458  def SetOutputMode(self, mode):
459  """Select which information to output."""
460  self._ensure_config_state()
461  data = struct.pack('!H', mode)
462  self.write_ack(MID.SetOutputMode, data)
463  self.mode = mode
464 
465  def GetExtOutputMode(self):
466  """Get current extended output mode (for alternative UART)."""
467  self._ensure_config_state()
468  data = self.write_ack(MID.SetExtOutputMode)
469  ext_mode, = struct.unpack('!H', data)
470  return ext_mode
471 
472  def SetExtOutputMode(self, ext_mode):
473  """Set extended output mode (for alternative UART)."""
474  self._ensure_config_state()
475  data = struct.pack('!H', ext_mode)
476  self.write_ack(MID.SetExtOutputMode, data)
477 
478  def GetOutputSettings(self):
479  """Get current output mode."""
480  self._ensure_config_state()
481  data = self.write_ack(MID.SetOutputSettings)
482  self.settings, = struct.unpack('!I', data)
483  return self.settings
484 
485  def SetOutputSettings(self, settings):
486  """Select how to output the information."""
487  self._ensure_config_state()
488  data = struct.pack('!I', settings)
489  self.write_ack(MID.SetOutputSettings, data)
490  self.settings = settings
491 
492  def SetOutputSkipFactor(self, skipfactor): # deprecated
493  """Set the output skip factor."""
494  self._ensure_config_state()
495  data = struct.pack('!H', skipfactor)
496  self.write_ack(DeprecatedMID.SetOutputSkipFactor, data)
497 
498  def ReqDataLength(self): # deprecated
499  """Get data length for mark III devices."""
500  self._ensure_config_state()
501  try:
502  data = self.write_ack(DeprecatedMID.ReqDataLength)
503  except MTErrorMessage as e:
504  if e.code == 0x04:
505  sys.stderr.write("ReqDataLength message is deprecated and not "
506  "recognised by your device.")
507  return
508  raise e
509  self.length, = struct.unpack('!H', data)
510  if self.length <= 254:
511  self.header = b'\xFA\xFF\x32' + struct.pack('!B', self.length)
512  else:
513  self.header = b'\xFA\xFF\x32\xFF' + struct.pack('!H', self.length)
514  return self.length
515 
516  def GetLatLonAlt(self):
517  """Get the stored position of the device.
518  It is used internally for local magnetic declination and local gravity.
519  """
520  self._ensure_config_state()
521  data = self.write_ack(MID.SetLatLonAlt)
522  if len(data) == 24:
523  lat, lon, alt = struct.unpack('!ddd', data)
524  elif len(data) == 12:
525  lat, lon, alt = struct.unpack('!fff', data)
526  else:
527  raise MTException('Could not parse ReqLatLonAltAck message: wrong'
528  'size of message.')
529  return (lat, lon, alt)
530 
531  def SetLatLonAlt(self, lat, lon, alt):
532  """Set the position of the device.
533  It is used internally for local magnetic declination and local gravity.
534  """
535  self._ensure_config_state()
536  data = struct.pack('!ddd', lat, lon, alt)
537  self.write_ack(MID.SetLatLonAlt, data)
538 
540  """Get the available XKF scenarios on the device."""
541  self._ensure_config_state()
542  data = self.write_ack(MID.ReqAvailableScenarios)
543  scenarios = []
544  try:
545  for i in range(len(data)/22):
546  scenario_type, version, label =\
547  struct.unpack('!BB20s', data[22*i:22*(i+1)])
548  scenarios.append((scenario_type, version, label.strip()))
549  # available XKF scenarios
550  self.scenarios = scenarios
551  except struct.error:
552  raise MTException("could not parse the available XKF scenarios.")
553  return scenarios
554 
556  """Get the ID of the currently used XKF scenario."""
557  self._ensure_config_state()
558  data = self.write_ack(MID.SetCurrentScenario)
559  _, self.scenario_id = struct.unpack('!BB', data) # version, id
560  return self.scenario_id
561 
562  def SetCurrentScenario(self, scenario_id):
563  """Sets the XKF scenario to use."""
564  self._ensure_config_state()
565  data = struct.pack('!BB', 0, scenario_id) # version, id
566  self.write_ack(MID.SetCurrentScenario, data)
567 
568  def ResetOrientation(self, code):
569  """Reset the orientation.
570 
571  Code can take several values:
572  0x0000: store current settings (only in config mode),
573  0x0001: heading reset (NOT supported by MTi-G),
574  0x0003: object reset.
575  """
576  data = struct.pack('!H', code)
577  self.write_ack(MID.ResetOrientation, data)
578 
579  def SetNoRotation(self, duration):
580  """Initiate the "no rotation" procedure to estimate gyro biases."""
582  data = struct.pack('!H', duration)
583  self.write_ack(MID.SetNoRotation, data)
584 
585  def GetUTCTime(self):
586  """Get UTC time from device."""
587  self._ensure_config_state()
588  data = self.write_ack(MID.SetUTCTime)
589  ns, year, month, day, hour, minute, second, flag = \
590  struct.unpack('!IHBBBBBB', data)
591  return (ns, year, month, day, hour, minute, second, flag)
592 
593  def SetUTCTime(self, ns, year, month, day, hour, minute, second, flag):
594  """Set UTC time on the device."""
595  self._ensure_config_state()
596  data = struct.pack('!IHBBBBBB', ns, year, month, day, hour, minute,
597  second, flag) # no clue what setting flag can mean
598  self.write_ack(MID.SetUTCTime, data)
599 
600  def AdjustUTCTime(self, ticks):
601  """Adjust UTC Time of device using correction ticks (0.1 ms)."""
602  self._ensure_config_state()
603  data = struct.pack('!i', ticks)
604  self.write(MID.AdjustUTCTime, data) # no ack mentioned in the doc
605 
606  ############################################################
607  # High-level utility functions
608  ############################################################
609  def configure_legacy(self, mode, settings, period=None, skipfactor=None):
610  """Configure the mode and settings of the MT device in legacy mode."""
611  try:
612  # switch mark IV devices to legacy mode
613  self.SetOutputConfiguration([(0x0000, 0)])
614  except MTErrorMessage as e:
615  if e.code == 0x04:
616  # mark III device
617  pass
618  else:
619  raise
620  except MTException as e:
621  if self.verbose:
622  print "no ack received while switching from MTData2 to MTData."
623  pass # no ack???
624  self.SetOutputMode(mode)
625  self.SetOutputSettings(settings)
626  if period is not None:
627  self.SetPeriod(period)
628  if skipfactor is not None:
629  self.SetOutputSkipFactor(skipfactor)
630  self.GetConfiguration()
631 
633  """Read configuration from device in legacy mode."""
634  self.GetConfiguration()
635  return self.mode, self.settings, self.length
636 
637  def read_measurement(self, mode=None, settings=None):
639  # getting data
640  # data = self.read_data_msg()
641  mid, data = self.read_msg()
642  if mid == MID.MTData:
643  return self.parse_MTData(data, mode, settings)
644  elif mid == MID.MTData2:
645  return self.parse_MTData2(data)
646  else:
647  raise MTException("unknown data message: mid=0x%02X (%s)." %
648  (mid, getMIDName(mid)))
649 
650  def parse_MTData2(self, data):
651  # Functions to parse each type of packet
652  def parse_temperature(data_id, content, ffmt):
653  o = {}
654  if (data_id & 0x00F0) == 0x10: # Temperature
655  o['Temp'], = struct.unpack('!'+ffmt, content)
656  else:
657  raise MTException("unknown packet: 0x%04X." % data_id)
658  return o
659 
660  def parse_timestamp(data_id, content, ffmt):
661  o = {}
662  if (data_id & 0x00F0) == 0x10: # UTC Time
663  o['ns'], o['Year'], o['Month'], o['Day'], o['Hour'],\
664  o['Minute'], o['Second'], o['Flags'] =\
665  struct.unpack('!LHBBBBBB', content)
666  elif (data_id & 0x00F0) == 0x20: # Packet Counter
667  o['PacketCounter'], = struct.unpack('!H', content)
668  elif (data_id & 0x00F0) == 0x30: # Integer Time of Week
669  o['TimeOfWeek'], = struct.unpack('!L', content)
670  elif (data_id & 0x00F0) == 0x40: # GPS Age # deprecated
671  o['gpsAge'], = struct.unpack('!B', content)
672  elif (data_id & 0x00F0) == 0x50: # Pressure Age # deprecated
673  o['pressureAge'], = struct.unpack('!B', content)
674  elif (data_id & 0x00F0) == 0x60: # Sample Time Fine
675  o['SampleTimeFine'], = struct.unpack('!L', content)
676  elif (data_id & 0x00F0) == 0x70: # Sample Time Coarse
677  o['SampleTimeCoarse'], = struct.unpack('!L', content)
678  elif (data_id & 0x00F0) == 0x80: # Frame Range
679  o['startFrame'], o['endFrame'] = struct.unpack('!HH', content)
680  else:
681  raise MTException("unknown packet: 0x%04X." % data_id)
682  return o
683 
684  def parse_orientation_data(data_id, content, ffmt):
685  o = {}
686  if (data_id & 0x000C) == 0x00: # ENU
687  o['frame'] = 'ENU'
688  elif (data_id & 0x000C) == 0x04: # NED
689  o['frame'] = 'NED'
690  elif (data_id & 0x000C) == 0x08: # NWU
691  o['frame'] = 'NWU'
692  if (data_id & 0x00F0) == 0x10: # Quaternion
693  o['Q0'], o['Q1'], o['Q2'], o['Q3'] = struct.unpack('!'+4*ffmt,
694  content)
695  elif (data_id & 0x00F0) == 0x20: # Rotation Matrix
696  o['a'], o['b'], o['c'], o['d'], o['e'], o['f'], o['g'], o['h'],\
697  o['i'] = struct.unpack('!'+9*ffmt, content)
698  elif (data_id & 0x00F0) == 0x30: # Euler Angles
699  o['Roll'], o['Pitch'], o['Yaw'] = struct.unpack('!'+3*ffmt,
700  content)
701  else:
702  raise MTException("unknown packet: 0x%04X." % data_id)
703  return o
704 
705  def parse_pressure(data_id, content, ffmt):
706  o = {}
707  if (data_id & 0x00F0) == 0x10: # Baro pressure
708  o['Pressure'], = struct.unpack('!L', content)
709  else:
710  raise MTException("unknown packet: 0x%04X." % data_id)
711  return o
712 
713  def parse_acceleration(data_id, content, ffmt):
714  o = {}
715  if (data_id & 0x000C) == 0x00: # ENU
716  o['frame'] = 'ENU'
717  elif (data_id & 0x000C) == 0x04: # NED
718  o['frame'] = 'NED'
719  elif (data_id & 0x000C) == 0x08: # NWU
720  o['frame'] = 'NWU'
721  if (data_id & 0x00F0) == 0x10: # Delta V
722  o['Delta v.x'], o['Delta v.y'], o['Delta v.z'] = \
723  struct.unpack('!'+3*ffmt, content)
724  elif (data_id & 0x00F0) == 0x20: # Acceleration
725  o['accX'], o['accY'], o['accZ'] = \
726  struct.unpack('!'+3*ffmt, content)
727  elif (data_id & 0x00F0) == 0x30: # Free Acceleration
728  o['freeAccX'], o['freeAccY'], o['freeAccZ'] = \
729  struct.unpack('!'+3*ffmt, content)
730  elif (data_id & 0x00F0) == 0x40: # AccelerationHR
731  o['accX'], o['accY'], o['accZ'] = \
732  struct.unpack('!'+3*ffmt, content)
733  else:
734  raise MTException("unknown packet: 0x%04X." % data_id)
735  return o
736 
737  def parse_position(data_id, content, ffmt):
738  o = {}
739  if (data_id & 0x000C) == 0x00: # ENU
740  o['frame'] = 'ENU'
741  elif (data_id & 0x000C) == 0x04: # NED
742  o['frame'] = 'NED'
743  elif (data_id & 0x000C) == 0x08: # NWU
744  o['frame'] = 'NWU'
745  if (data_id & 0x00F0) == 0x10: # Altitude MSL # deprecated
746  o['altMsl'], = struct.unpack('!'+ffmt, content)
747  elif (data_id & 0x00F0) == 0x20: # Altitude Ellipsoid
748  o['altEllipsoid'], = struct.unpack('!'+ffmt, content)
749  elif (data_id & 0x00F0) == 0x30: # Position ECEF
750  o['ecefX'], o['ecefY'], o['ecefZ'] = \
751  struct.unpack('!'+3*ffmt, content)
752  elif (data_id & 0x00F0) == 0x40: # LatLon
753  o['lat'], o['lon'] = struct.unpack('!'+2*ffmt, content)
754  else:
755  raise MTException("unknown packet: 0x%04X." % data_id)
756  return o
757 
758  def parse_GNSS(data_id, content, ffmt):
759  o = {}
760  if (data_id & 0x00F0) == 0x10: # GNSS PVT data
761  o['itow'], o['year'], o['month'], o['day'], o['hour'],\
762  o['min'], o['sec'], o['valid'], o['tAcc'], o['nano'],\
763  o['fixtype'], o['flags'], o['numSV'], o['lon'], o['lat'],\
764  o['height'], o['hMSL'], o['hAcc'], o['vAcc'], o['velN'],\
765  o['velE'], o['velD'], o['gSpeed'], o['headMot'], o['sAcc'],\
766  o['headAcc'], o['headVeh'], o['gdop'], o['pdop'],\
767  o['tdop'], o['vdop'], o['hdop'], o['ndop'], o['edop'] = \
768  struct.unpack('!IHBBBBBBIiBBBxiiiiIIiiiiiIIiHHHHHHH',
769  content)
770  # scaling correction
771  o['lon'] *= 1e-7
772  o['lat'] *= 1e-7
773  o['headMot'] *= 1e-5
774  o['headVeh'] *= 1e-5
775  o['gdop'] *= 0.01
776  o['pdop'] *= 0.01
777  o['tdop'] *= 0.01
778  o['vdop'] *= 0.01
779  o['hdop'] *= 0.01
780  o['ndop'] *= 0.01
781  o['edop'] *= 0.01
782  elif (data_id & 0x00F0) == 0x20: # GNSS satellites info
783  o['iTOW'], o['numSvs'] = struct.unpack('!LBxxx', content[:8])
784  svs = []
785  ch = {}
786  for i in range(o['numSvs']):
787  ch['gnssId'], ch['svId'], ch['cno'], ch['flags'] = \
788  struct.unpack('!BBBB', content[8+4*i:12+4*i])
789  svs.append(ch)
790  o['svs'] = svs
791  else:
792  raise MTException("unknown packet: 0x%04X." % data_id)
793  return o
794 
795  def parse_angular_velocity(data_id, content, ffmt):
796  o = {}
797  if (data_id & 0x000C) == 0x00: # ENU
798  o['frame'] = 'ENU'
799  elif (data_id & 0x000C) == 0x04: # NED
800  o['frame'] = 'NED'
801  elif (data_id & 0x000C) == 0x08: # NWU
802  o['frame'] = 'NWU'
803  if (data_id & 0x00F0) == 0x20: # Rate of Turn
804  o['gyrX'], o['gyrY'], o['gyrZ'] = \
805  struct.unpack('!'+3*ffmt, content)
806  elif (data_id & 0x00F0) == 0x30: # Delta Q
807  o['Delta q0'], o['Delta q1'], o['Delta q2'], o['Delta q3'] = \
808  struct.unpack('!'+4*ffmt, content)
809  elif (data_id & 0x00F0) == 0x40: # RateOfTurnHR
810  o['gyrX'], o['gyrY'], o['gyrZ'] = \
811  struct.unpack('!'+3*ffmt, content)
812  else:
813  raise MTException("unknown packet: 0x%04X." % data_id)
814  return o
815 
816  def parse_GPS(data_id, content, ffmt):
817  o = {}
818  if (data_id & 0x00F0) == 0x30: # DOP
819  o['iTOW'], g, p, t, v, h, n, e = \
820  struct.unpack('!LHHHHHHH', content)
821  o['gDOP'], o['pDOP'], o['tDOP'], o['vDOP'], o['hDOP'], \
822  o['nDOP'], o['eDOP'] = 0.01*g, 0.01*p, 0.01*t, \
823  0.01*v, 0.01*h, 0.01*n, 0.01*e
824  elif (data_id & 0x00F0) == 0x40: # SOL
825  o['iTOW'], o['fTOW'], o['Week'], o['gpsFix'], o['Flags'], \
826  o['ecefX'], o['ecefY'], o['ecefZ'], o['pAcc'], \
827  o['ecefVX'], o['ecefVY'], o['ecefVZ'], o['sAcc'], \
828  o['pDOP'], o['numSV'] = \
829  struct.unpack('!LlhBBlllLlllLHxBx', content)
830  # scaling correction
831  o['pDOP'] *= 0.01
832  elif (data_id & 0x00F0) == 0x80: # Time UTC
833  o['iTOW'], o['tAcc'], o['nano'], o['year'], o['month'], \
834  o['day'], o['hour'], o['min'], o['sec'], o['valid'] = \
835  struct.unpack('!LLlHBBBBBB', content)
836  elif (data_id & 0x00F0) == 0xA0: # SV Info
837  o['iTOW'], o['numCh'] = struct.unpack('!LBxxx', content[:8])
838  channels = []
839  ch = {}
840  for i in range(o['numCh']):
841  ch['chn'], ch['svid'], ch['flags'], ch['quality'], \
842  ch['cno'], ch['elev'], ch['azim'], ch['prRes'] = \
843  struct.unpack('!BBBBBbhl', content[8+12*i:20+12*i])
844  channels.append(ch)
845  o['channels'] = channels
846  else:
847  raise MTException("unknown packet: 0x%04X." % data_id)
848  return o
849 
850  def parse_SCR(data_id, content, ffmt):
851  o = {}
852  if (data_id & 0x00F0) == 0x10: # ACC+GYR+MAG+Temperature
853  o['accX'], o['accY'], o['accZ'], o['gyrX'], o['gyrY'], \
854  o['gyrZ'], o['magX'], o['magY'], o['magZ'], o['Temp'] = \
855  struct.unpack("!9Hh", content)
856  elif (data_id & 0x00F0) == 0x20: # Gyro Temperature
857  o['tempGyrX'], o['tempGyrY'], o['tempGyrZ'] = \
858  struct.unpack("!hhh", content)
859  else:
860  raise MTException("unknown packet: 0x%04X." % data_id)
861  return o
862 
863  def parse_analog_in(data_id, content, ffmt): # deprecated
864  o = {}
865  if (data_id & 0x00F0) == 0x10: # Analog In 1
866  o['analogIn1'], = struct.unpack("!H", content)
867  elif (data_id & 0x00F0) == 0x20: # Analog In 2
868  o['analogIn2'], = struct.unpack("!H", content)
869  else:
870  raise MTException("unknown packet: 0x%04X." % data_id)
871  return o
872 
873  def parse_magnetic(data_id, content, ffmt):
874  o = {}
875  if (data_id & 0x000C) == 0x00: # ENU
876  o['frame'] = 'ENU'
877  elif (data_id & 0x000C) == 0x04: # NED
878  o['frame'] = 'NED'
879  elif (data_id & 0x000C) == 0x08: # NWU
880  o['frame'] = 'NWU'
881  if (data_id & 0x00F0) == 0x20: # Magnetic Field
882  o['magX'], o['magY'], o['magZ'] = \
883  struct.unpack("!3"+ffmt, content)
884  else:
885  raise MTException("unknown packet: 0x%04X." % data_id)
886  return o
887 
888  def parse_velocity(data_id, content, ffmt):
889  o = {}
890  if (data_id & 0x000C) == 0x00: # ENU
891  o['frame'] = 'ENU'
892  elif (data_id & 0x000C) == 0x04: # NED
893  o['frame'] = 'NED'
894  elif (data_id & 0x000C) == 0x08: # NWU
895  o['frame'] = 'NWU'
896  if (data_id & 0x00F0) == 0x10: # Velocity XYZ
897  o['velX'], o['velY'], o['velZ'] = \
898  struct.unpack("!3"+ffmt, content)
899  else:
900  raise MTException("unknown packet: 0x%04X." % data_id)
901  return o
902 
903  def parse_status(data_id, content, ffmt):
904  o = {}
905  if (data_id & 0x00F0) == 0x10: # Status Byte
906  o['StatusByte'], = struct.unpack("!B", content)
907  elif (data_id & 0x00F0) == 0x20: # Status Word
908  o['StatusWord'], = struct.unpack("!L", content)
909  elif (data_id & 0x00F0) == 0x40: # RSSI # deprecated
910  o['RSSI'], = struct.unpack("!b", content)
911  else:
912  raise MTException("unknown packet: 0x%04X." % data_id)
913  return o
914 
915  # data object
916  output = {}
917  while data:
918  try:
919  data_id, size = struct.unpack('!HB', data[:3])
920  if (data_id & 0x0003) == 0x3:
921  float_format = 'd'
922  elif (data_id & 0x0003) == 0x0:
923  float_format = 'f'
924  else:
925  raise MTException("fixed point precision not supported.")
926  content = data[3:3+size]
927  data = data[3+size:]
928  group = data_id & 0xF800
929  ffmt = float_format
930  if group == XDIGroup.Temperature:
931  output.setdefault('Temperature', {}).update(
932  parse_temperature(data_id, content, ffmt))
933  elif group == XDIGroup.Timestamp:
934  output.setdefault('Timestamp', {}).update(
935  parse_timestamp(data_id, content, ffmt))
936  elif group == XDIGroup.OrientationData:
937  output.setdefault('Orientation Data', {}).update(
938  parse_orientation_data(data_id, content, ffmt))
939  elif group == XDIGroup.Pressure:
940  output.setdefault('Pressure', {}).update(
941  parse_pressure(data_id, content, ffmt))
942  elif group == XDIGroup.Acceleration:
943  output.setdefault('Acceleration', {}).update(
944  parse_acceleration(data_id, content, ffmt))
945  elif group == XDIGroup.Position:
946  output.setdefault('Position', {}).update(
947  parse_position(data_id, content, ffmt))
948  elif group == XDIGroup.GNSS:
949  output.setdefault('GNSS', {}).update(
950  parse_GNSS(data_id, content, ffmt))
951  elif group == XDIGroup.AngularVelocity:
952  output.setdefault('Angular Velocity', {}).update(
953  parse_angular_velocity(data_id, content, ffmt))
954  elif group == XDIGroup.GPS:
955  output.setdefault('GPS', {}).update(
956  parse_GPS(data_id, content, ffmt))
957  elif group == XDIGroup.SensorComponentReadout:
958  output.setdefault('SCR', {}).update(
959  parse_SCR(data_id, content, ffmt))
960  elif group == XDIGroup.AnalogIn: # deprecated
961  output.setdefault('Analog In', {}).update(
962  parse_analog_in(data_id, content, ffmt))
963  elif group == XDIGroup.Magnetic:
964  output.setdefault('Magnetic', {}).update(
965  parse_magnetic(data_id, content, ffmt))
966  elif group == XDIGroup.Velocity:
967  output.setdefault('Velocity', {}).update(
968  parse_velocity(data_id, content, ffmt))
969  elif group == XDIGroup.Status:
970  output.setdefault('Status', {}).update(
971  parse_status(data_id, content, ffmt))
972  else:
973  raise MTException("unknown XDI group: 0x%04X." % group)
974  except struct.error:
975  raise MTException("couldn't parse MTData2 message.")
976  return output
977 
978  def parse_MTData(self, data, mode=None, settings=None):
979  """Read and parse a legacy measurement packet."""
980  # getting mode
981  if mode is None:
982  mode = self.mode
983  if settings is None:
984  settings = self.settings
985  # data object
986  output = {}
987  try:
988  # raw IMU first
989  if mode & OutputMode.RAW:
990  o = {}
991  o['accX'], o['accY'], o['accZ'], o['gyrX'], o['gyrY'], \
992  o['gyrZ'], o['magX'], o['magY'], o['magZ'], o['temp'] =\
993  struct.unpack('!10H', data[:20])
994  data = data[20:]
995  output['RAW'] = o
996  # raw GPS second
997  if mode & OutputMode.RAWGPS:
998  o = {}
999  o['Press'], o['bPrs'], o['ITOW'], o['LAT'], o['LON'], o['ALT'],\
1000  o['VEL_N'], o['VEL_E'], o['VEL_D'], o['Hacc'], o['Vacc'],\
1001  o['Sacc'], o['bGPS'] = struct.unpack('!HBI6i3IB', data[:44])
1002  data = data[44:]
1003  output['RAWGPS'] = o
1004  # temperature
1005  if mode & OutputMode.Temp:
1006  temp, = struct.unpack('!f', data[:4])
1007  data = data[4:]
1008  output['Temp'] = temp
1009  # calibrated data
1010  if mode & OutputMode.Calib:
1011  o = {}
1012  if (settings & OutputSettings.Coordinates_NED):
1013  o['frame'] = 'NED'
1014  else:
1015  o['frame'] = 'ENU'
1016  if not (settings & OutputSettings.CalibMode_GyrMag):
1017  o['accX'], o['accY'], o['accZ'] = struct.unpack('!3f',
1018  data[:12])
1019  data = data[12:]
1020  if not (settings & OutputSettings.CalibMode_AccMag):
1021  o['gyrX'], o['gyrY'], o['gyrZ'] = struct.unpack('!3f',
1022  data[:12])
1023  data = data[12:]
1024  if not (settings & OutputSettings.CalibMode_AccGyr):
1025  o['magX'], o['magY'], o['magZ'] = struct.unpack('!3f',
1026  data[:12])
1027  data = data[12:]
1028  output['Calib'] = o
1029  # orientation
1030  if mode & OutputMode.Orient:
1031  o = {}
1032  if (settings & OutputSettings.Coordinates_NED):
1033  o['frame'] = 'NED'
1034  else:
1035  o['frame'] = 'ENU'
1036  if settings & OutputSettings.OrientMode_Euler:
1037  o['roll'], o['pitch'], o['yaw'] = struct.unpack('!3f',
1038  data[:12])
1039  data = data[12:]
1040  elif settings & OutputSettings.OrientMode_Matrix:
1041  a, b, c, d, e, f, g, h, i = struct.unpack('!9f',
1042  data[:36])
1043  data = data[36:]
1044  o['matrix'] = ((a, b, c), (d, e, f), (g, h, i))
1045  else: # OutputSettings.OrientMode_Quaternion:
1046  q0, q1, q2, q3 = struct.unpack('!4f', data[:16])
1047  data = data[16:]
1048  o['quaternion'] = (q0, q1, q2, q3)
1049  output['Orient'] = o
1050  # auxiliary
1051  if mode & OutputMode.Auxiliary:
1052  o = {}
1053  if not (settings & OutputSettings.AuxiliaryMode_NoAIN1):
1054  o['Ain_1'], = struct.unpack('!H', data[:2])
1055  data = data[2:]
1056  if not (settings & OutputSettings.AuxiliaryMode_NoAIN2):
1057  o['Ain_2'], = struct.unpack('!H', data[:2])
1058  data = data[2:]
1059  output['Auxiliary'] = o
1060  # position
1061  if mode & OutputMode.Position:
1062  o = {}
1063  o['Lat'], o['Lon'], o['Alt'] = struct.unpack('!3f', data[:12])
1064  data = data[12:]
1065  output['Pos'] = o
1066  # velocity
1067  if mode & OutputMode.Velocity:
1068  o = {}
1069  if (settings & OutputSettings.Coordinates_NED):
1070  o['frame'] = 'NED'
1071  else:
1072  o['frame'] = 'ENU'
1073  o['Vel_X'], o['Vel_Y'], o['Vel_Z'] = struct.unpack('!3f',
1074  data[:12])
1075  data = data[12:]
1076  output['Vel'] = o
1077  # status
1078  if mode & OutputMode.Status:
1079  status, = struct.unpack('!B', data[:1])
1080  data = data[1:]
1081  output['Stat'] = status
1082  # sample counter
1083  if settings & OutputSettings.Timestamp_SampleCnt:
1084  TS, = struct.unpack('!H', data[:2])
1085  data = data[2:]
1086  output['Sample'] = TS
1087  # UTC time
1088  if settings & OutputSettings.Timestamp_UTCTime:
1089  o = {}
1090  o['ns'], o['Year'], o['Month'], o['Day'], o['Hour'],\
1091  o['Minute'], o['Second'], o['Flags'] = struct.unpack(
1092  '!ihbbbbb', data[:12])
1093  data = data[12:]
1094  output['Timestamp'] = o
1095  # TODO at that point data should be empty
1096  except struct.error, e:
1097  raise MTException("could not parse MTData message.")
1098  if data != '':
1099  raise MTException("could not parse MTData message (too long).")
1100  return output
1101 
1102  def ChangeBaudrate(self, baudrate):
1103  """Change the baudrate, reset the device and reopen communication."""
1104  brid = Baudrates.get_BRID(baudrate)
1105  self.SetBaudrate(brid)
1106  self.Reset()
1107  # self.device.flush()
1108  self.device.baudrate = baudrate
1109  # self.device.flush()
1110  time.sleep(0.01)
1111  self.read_msg()
1112  self.write_msg(MID.WakeUpAck)
1113 
1114 
1115 ################################################################
1116 # Auto detect port
1117 ################################################################
1118 def find_devices(timeout=0.002, verbose=False, initial_wait=0.1):
1119  mtdev_list = []
1120  for port in glob.glob("/dev/tty*S*"):
1121  if verbose:
1122  print "Trying '%s'" % port
1123  try:
1124  br = find_baudrate(port, timeout, verbose, initial_wait)
1125  if br:
1126  mtdev_list.append((port, br))
1127  except MTException:
1128  pass
1129  return mtdev_list
1130 
1131 
1132 ################################################################
1133 # Auto detect baudrate
1134 ################################################################
1135 def find_baudrate(port, timeout=0.002, verbose=False, initial_wait=0.1):
1136  baudrates = (115200, 460800, 921600, 230400, 57600, 38400, 19200, 9600)
1137  for br in baudrates:
1138  if verbose:
1139  print "Trying %d bd:" % br,
1140  sys.stdout.flush()
1141  try:
1142  mt = MTDevice(port, br, timeout=timeout, verbose=verbose,
1143  initial_wait=initial_wait)
1144  except serial.SerialException:
1145  if verbose:
1146  print "fail: unable to open device."
1147  raise MTException("unable to open %s" % port)
1148  try:
1149  mt.GoToConfig()
1150  mt.GoToMeasurement()
1151  if verbose:
1152  print "ok."
1153  return br
1154  except MTException:
1155  if verbose:
1156  print "fail."
1157 
1158 
1159 ################################################################
1160 # Documentation for stand alone usage
1161 ################################################################
1162 def usage():
1163  print """MT device driver.
1164 Usage:
1165  ./mtdevice.py [commands] [opts]
1166 
1167 Commands:
1168  -h, --help
1169  Print this help and quit.
1170  -r, --reset
1171  Reset device to factory defaults.
1172  -a, --change-baudrate=NEW_BAUD
1173  Change baudrate from BAUD (see below) to NEW_BAUD.
1174  -c, --configure=OUTPUT
1175  Configure the device (see OUTPUT description below).
1176  -e, --echo
1177  Print MTData. It is the default if no other command is supplied.
1178  -i, --inspect
1179  Print current MT device configuration.
1180  -x, --xkf-scenario=ID
1181  Change the current XKF scenario.
1182  -l, --legacy-configure
1183  Configure the device in legacy mode (needs MODE and SETTINGS arguments
1184  below).
1185  -v, --verbose
1186  Verbose output.
1187  -y, --synchronization=settings (see below)
1188  Configure the synchronization settings of each sync line (see below)
1189  -u, --setUTCTime=time (see below)
1190  Sets the UTC time buffer of the device
1191 
1192 Generic options:
1193  -d, --device=DEV
1194  Serial interface of the device (default: /dev/ttyUSB0). If 'auto', then
1195  all serial ports are tested at all baudrates and the first
1196  suitable device is used.
1197  -b, --baudrate=BAUD
1198  Baudrate of serial interface (default: 115200). If 0, then all
1199  rates are tried until a suitable one is found.
1200  -t, --timeout=TIMEOUT
1201  Timeout of serial communication in second (default: 0.002).
1202  -w, --initial-wait=WAIT
1203  Initial wait to allow device to be ready in second (default: 0.1).
1204 
1205 Configuration option:
1206  OUTPUT
1207  The format is a sequence of "<group><type><frequency>?<format>?"
1208  separated by commas.
1209  The frequency and format are optional.
1210  The groups and types can be:
1211  t temperature (max frequency: 1 Hz):
1212  tt temperature
1213  i timestamp (max frequency: 2000 Hz):
1214  iu UTC time
1215  ip packet counter
1216  ii Integer Time of the Week (ITOW)
1217  if sample time fine
1218  ic sample time coarse
1219  ir frame range
1220  o orientation data (max frequency: 400 Hz):
1221  oq quaternion
1222  om rotation matrix
1223  oe Euler angles
1224  b pressure (max frequency: 50 Hz):
1225  bp baro pressure
1226  a acceleration (max frequency: 2000 Hz (see documentation)):
1227  ad delta v
1228  aa acceleration
1229  af free acceleration
1230  ah acceleration HR (max frequency 1000 Hz)
1231  p position (max frequency: 400 Hz):
1232  pa altitude ellipsoid
1233  pp position ECEF
1234  pl latitude longitude
1235  n GNSS (max frequency: 4 Hz):
1236  np GNSS PVT data
1237  ns GNSS satellites info
1238  w angular velocity (max frequency: 2000 Hz (see documentation)):
1239  wr rate of turn
1240  wd delta q
1241  wh rate of turn HR (max frequency 1000 Hz)
1242  g GPS (max frequency: 4 Hz):
1243  gd DOP
1244  gs SOL
1245  gu time UTC
1246  gi SV info
1247  r Sensor Component Readout (max frequency: 2000 Hz):
1248  rr ACC, GYR, MAG, temperature
1249  rt Gyro temperatures
1250  m Magnetic (max frequency: 100 Hz):
1251  mf magnetic Field
1252  v Velocity (max frequency: 400 Hz):
1253  vv velocity XYZ
1254  s Status (max frequency: 2000 Hz):
1255  sb status byte
1256  sw status word
1257  Frequency is specified in decimal and is assumed to be the maximum
1258  frequency if it is omitted.
1259  Format is a combination of the precision for real valued numbers and
1260  coordinate system:
1261  precision:
1262  f single precision floating point number (32-bit) (default)
1263  d double precision floating point number (64-bit)
1264  coordinate system:
1265  e East-North-Up (default)
1266  n North-East-Down
1267  w North-West-Up
1268  Examples:
1269  The default configuration for the MTi-1/10/100 IMUs can be
1270  specified either as:
1271  "wd,ad,mf,ip,if,sw"
1272  or
1273  "wd2000fe,ad2000fe,mf100fe,ip2000,if2000,sw2000"
1274  For getting quaternion orientation in float with sample time:
1275  "oq400fw,if2000"
1276  For longitude, latitude, altitude and orientation (on MTi-G-700):
1277  "pl400fe,pa400fe,oq400fe"
1278 
1279 Synchronization settings:
1280  The format follows the xsens protocol documentation. All fields are required
1281  and separated by commas.
1282  Note: The entire synchronization buffer is wiped every time a new one
1283  is set, so it is necessary to specify the settings of multiple
1284  lines at once.
1285  It also possible to clear the synchronization with the argument "clear"
1286 
1287  Function (see manual for details):
1288  3 Trigger indication
1289  4 Interval Transition Measurement
1290  8 SendLatest
1291  9 ClockBiasEstimation
1292  11 StartSampling
1293  Line (manual for details):
1294  0 ClockIn
1295  1 GPSClockIn (only available for 700/710)
1296  2 Input Line (SyncIn)
1297  4 SyncOut
1298  5 ExtTimepulseIn (only available for 700/710)
1299  6 Software (only available for SendLatest with ReqData message)
1300  Polarity:
1301  1 Positive pulse/ Rising edge
1302  2 Negative pulse/ Falling edge
1303  3 Both/ Toggle
1304  Trigger Type:
1305  0 multiple times
1306  1 once
1307  Skip First (unsigned_int):
1308  Number of initial events to skip before taking actions
1309  Skip Factor (unsigned_int):
1310  Number of events to skip before taking action again
1311  Ignored with ReqData.
1312  Pulse Width (unsigned_int):
1313  Ignored for SyncIn.
1314  For SyncOut, the width of the generated pulse in 100 microseconds
1315  unit. Ignored for Toggle pulses.
1316  Delay:
1317  Delay after receiving a sync pulse to taking action,
1318  100 microseconds units, range [0...600000]
1319  Clock Period:
1320  Reference clock period in milliseconds for ClockBiasEstimation
1321  Offset:
1322  Offset from event to pulse generation.
1323  100 microseconds unit, range [-30000...+30000]
1324 
1325  Examples:
1326  For changing the sync setting of the SyncIn line to trigger indication
1327  with rising edge, one time triggering and no skipping and delay. Enter
1328  the settings as:
1329  "3,2,1,1,0,0,0,0"
1330 
1331  Note a number is still in the place for pulse width despite it being
1332  ignored.
1333 
1334  To set multiple lines at once:
1335  ./mtdevice.py -y 3,2,1,0,0,0,0,0 -y 9,0,1,0,0,0,10,0
1336 
1337  To clear the synchronization settings of MTi
1338  ./mtdevice.py -y clear
1339 
1340 SetUTCTime settings:
1341  There are two ways to set the UTCtime for the MTi.
1342  Option #1: set MTi to the current UTC time based on local system time with
1343  the option 'now'
1344  Option #2: set MTi to a specified UTC time
1345  The time fields are set as follows:
1346  year: range [1999,2099]
1347  month: range [1,12]
1348  day: day of the month, range [1,31]
1349  hour: hour of the day, range [0,23]
1350  min: minute of the hour, range [0,59]
1351  sec: second of the minute, range [0,59]
1352  ns: nanosecond of the second, range [0,1000000000]
1353  flag:
1354  1: Valid Time of Week
1355  2: Valid Week Number
1356  4: valid UTC
1357  Note: the flag is ignored for setUTCTime as it is set by the module
1358  itself when connected to a GPS
1359 
1360  Examples:
1361  Set UTC time for the device:
1362  ./mtdevice.py -u now
1363  ./mtdevice.py -u 1999,1,1,0,0,0,0,0
1364 
1365 Legacy options:
1366  -m, --output-mode=MODE
1367  Legacy mode of the device to select the information to output.
1368  This is required for 'legacy-configure' command.
1369  MODE can be either the mode value in hexadecimal, decimal or
1370  binary form, or a string composed of the following characters
1371  (in any order):
1372  t temperature, [0x0001]
1373  c calibrated data, [0x0002]
1374  o orientation data, [0x0004]
1375  a auxiliary data, [0x0008]
1376  p position data (requires MTi-G), [0x0010]
1377  v velocity data (requires MTi-G), [0x0020]
1378  s status data, [0x0800]
1379  g raw GPS mode (requires MTi-G), [0x1000]
1380  r raw (incompatible with others except raw GPS), [0x4000]
1381  For example, use "--output-mode=so" to have status and
1382  orientation data.
1383  -s, --output-settings=SETTINGS
1384  Legacy settings of the device. This is required for 'legacy-configure'
1385  command.
1386  SETTINGS can be either the settings value in hexadecimal,
1387  decimal or binary form, or a string composed of the following
1388  characters (in any order):
1389  t sample count (excludes 'n')
1390  n no sample count (excludes 't')
1391  u UTC time
1392  q orientation in quaternion (excludes 'e' and 'm')
1393  e orientation in Euler angles (excludes 'm' and 'q')
1394  m orientation in matrix (excludes 'q' and 'e')
1395  A acceleration in calibrated data
1396  G rate of turn in calibrated data
1397  M magnetic field in calibrated data
1398  i only analog input 1 (excludes 'j')
1399  j only analog input 2 (excludes 'i')
1400  N North-East-Down instead of default: X North Z up
1401  For example, use "--output-settings=tqMAG" for all calibrated
1402  data, sample counter and orientation in quaternion.
1403  -p, --period=PERIOD
1404  Sampling period in (1/115200) seconds (default: 1152).
1405  Minimum is 225 (1.95 ms, 512 Hz), maximum is 1152
1406  (10.0 ms, 100 Hz).
1407  Note that for legacy devices it is the period at which sampling occurs,
1408  not the period at which messages are sent (see below).
1409 
1410 Deprecated options:
1411  -f, --deprecated-skip-factor=SKIPFACTOR
1412  Only for mark III devices.
1413  Number of samples to skip before sending MTData message
1414  (default: 0).
1415  The frequency at which MTData message is send is:
1416  115200/(PERIOD * (SKIPFACTOR + 1))
1417  If the value is 0xffff, no data is send unless a ReqData request
1418  is made.
1419 """
1420 
1421 
1422 ################################################################
1423 # Main function
1424 ################################################################
1425 def main():
1426  # parse command line
1427  shopts = 'hra:c:eild:b:y:u:m:s:p:f:x:vt:w:'
1428  lopts = ['help', 'reset', 'change-baudrate=', 'configure=', 'echo',
1429  'inspect', 'legacy-configure', 'device=', 'baudrate=',
1430  'output-mode=', 'output-settings=', 'period=',
1431  'deprecated-skip-factor=', 'xkf-scenario=', 'verbose',
1432  'synchronization=', 'setUTCtime=', 'timeout=', 'initial-wait=']
1433  try:
1434  opts, args = getopt.gnu_getopt(sys.argv[1:], shopts, lopts)
1435  except getopt.GetoptError, e:
1436  print e
1437  usage()
1438  return 1
1439  # default values
1440  device = '/dev/ttyUSB0'
1441  baudrate = 115200
1442  timeout = 0.002
1443  initial_wait = 0.1
1444  mode = None
1445  settings = None
1446  period = None
1447  skipfactor = None
1448  new_baudrate = None
1449  new_xkf = None
1450  actions = []
1451  verbose = False
1452  sync_settings = [] # list of synchronization settings
1453 
1454  # filling in arguments
1455  for o, a in opts:
1456  if o in ('-h', '--help'):
1457  usage()
1458  return
1459  elif o in ('-r', '--reset'):
1460  actions.append('reset')
1461  elif o in ('-a', '--change-baudrate'):
1462  try:
1463  new_baudrate = int(a)
1464  except ValueError:
1465  print "change-baudrate argument must be integer."
1466  return 1
1467  actions.append('change-baudrate')
1468  elif o in ('-c', '--configure'):
1469  output_config = get_output_config(a)
1470  if output_config is None:
1471  return 1
1472  actions.append('configure')
1473  elif o in ('-e', '--echo'):
1474  actions.append('echo')
1475  elif o in ('-i', '--inspect'):
1476  actions.append('inspect')
1477  elif o in ('-l', '--legacy-configure'):
1478  actions.append('legacy-configure')
1479  elif o in ('-x', '--xkf-scenario'):
1480  try:
1481  new_xkf = int(a)
1482  except ValueError:
1483  print "xkf-scenario argument must be integer."
1484  return 1
1485  actions.append('xkf-scenario')
1486  elif o in ('-y', '--synchronization'):
1487  new_sync_settings = get_synchronization_settings(a)
1488  if new_sync_settings is None:
1489  return 1
1490  sync_settings.append(new_sync_settings)
1491  actions.append('synchronization')
1492  elif o in ('-u', '--setUTCtime'):
1493  UTCtime_settings = get_UTCtime(a)
1494  if UTCtime_settings is None:
1495  return 1
1496  actions.append('setUTCtime')
1497  elif o in ('-d', '--device'):
1498  device = a
1499  elif o in ('-b', '--baudrate'):
1500  try:
1501  baudrate = int(a)
1502  except ValueError:
1503  print "baudrate argument must be integer."
1504  return 1
1505  elif o in ('-m', '--output-mode'):
1506  mode = get_mode(a)
1507  if mode is None:
1508  return 1
1509  elif o in ('-s', '--output-settings'):
1510  settings = get_settings(a)
1511  if settings is None:
1512  return 1
1513  elif o in ('-p', '--period'):
1514  try:
1515  period = int(a)
1516  except ValueError:
1517  print "period argument must be integer."
1518  return 1
1519  elif o in ('-f', '--deprecated-skip-factor'):
1520  try:
1521  skipfactor = int(a)
1522  except ValueError:
1523  print "skip-factor argument must be integer."
1524  return 1
1525  elif o in ('-v', '--verbose'):
1526  verbose = True
1527  elif o in ('-t', '--timeout'):
1528  try:
1529  timeout = float(a)
1530  except ValueError:
1531  print "timeout argument must be a floating number."
1532  return 1
1533  elif o in ('-w', '--initial-wait'):
1534  try:
1535  initial_wait = float(a)
1536  except ValueError:
1537  print "initial-wait argument must be a floating number."
1538  return 1
1539 
1540  # if nothing else: echo
1541  if len(actions) == 0:
1542  actions.append('echo')
1543  try:
1544  if device == 'auto':
1545  devs = find_devices(timeout=timeout, verbose=verbose,
1546  initial_wait=initial_wait)
1547  if devs:
1548  print "Detected devices:", "".join('\n\t%s @ %d' % (d, p)
1549  for d, p in devs)
1550  print "Using %s @ %d" % devs[0]
1551  device, baudrate = devs[0]
1552  else:
1553  print "No suitable device found."
1554  return 1
1555  # find baudrate
1556  if not baudrate:
1557  baudrate = find_baudrate(device, timeout=timeout, verbose=verbose,
1558  initial_wait=initial_wait)
1559  if not baudrate:
1560  print "No suitable baudrate found."
1561  return 1
1562  # open device
1563  try:
1564  mt = MTDevice(device, baudrate, timeout=timeout, verbose=verbose,
1565  initial_wait=initial_wait)
1566  except serial.SerialException:
1567  raise MTException("unable to open %s" % device)
1568  # execute actions
1569  if 'inspect' in actions:
1570  inspect(mt, device, baudrate)
1571  if 'change-baudrate' in actions:
1572  print "Changing baudrate from %d to %d:" % (baudrate, new_baudrate),
1573  sys.stdout.flush()
1574  mt.ChangeBaudrate(new_baudrate)
1575  print " Ok" # should we test that it was actually ok?
1576  if 'reset' in actions:
1577  print "Restoring factory defaults",
1578  sys.stdout.flush()
1579  mt.RestoreFactoryDefaults()
1580  print " Ok" # should we test that it was actually ok?
1581  if 'configure' in actions:
1582  print "Changing output configuration",
1583  sys.stdout.flush()
1584  mt.SetOutputConfiguration(output_config)
1585  print " Ok" # should we test that it was actually ok?
1586  if 'synchronization' in actions:
1587  print "Changing synchronization settings",
1588  sys.stdout.flush()
1589  mt.SetSyncSettings(sync_settings)
1590  print " Ok" # should we test that it was actually ok?
1591  if 'setUTCtime' in actions:
1592  print "Setting UTC time in the device",
1593  sys.stdout.flush()
1594  mt.SetUTCTime(UTCtime_settings[6],
1595  UTCtime_settings[0],
1596  UTCtime_settings[1],
1597  UTCtime_settings[2],
1598  UTCtime_settings[3],
1599  UTCtime_settings[4],
1600  UTCtime_settings[5],
1601  UTCtime_settings[7])
1602  print " Ok" # should we test that it was actually ok?
1603  if 'legacy-configure' in actions:
1604  if mode is None:
1605  print "output-mode is require to configure the device in "\
1606  "legacy mode."
1607  return 1
1608  if settings is None:
1609  print "output-settings is required to configure the device in "\
1610  "legacy mode."
1611  return 1
1612  print "Configuring in legacy mode",
1613  sys.stdout.flush()
1614  mt.configure_legacy(mode, settings, period, skipfactor)
1615  print " Ok" # should we test it was actually ok?
1616  if 'xkf-scenario' in actions:
1617  print "Changing XKF scenario",
1618  sys.stdout.flush()
1619  mt.SetCurrentScenario(new_xkf)
1620  print "Ok"
1621  if 'echo' in actions:
1622  # if (mode is None) or (settings is None):
1623  # mode, settings, length = mt.auto_config()
1624  # print mode, settings, length
1625  try:
1626  while True:
1627  print mt.read_measurement(mode, settings)
1628  except KeyboardInterrupt:
1629  pass
1630  except MTErrorMessage as e:
1631  print "MTErrorMessage:", e
1632  except MTException as e:
1633  print "MTException:", e
1634 
1635 
1636 def inspect(mt, device, baudrate):
1637  """Inspection."""
1638  def config_fmt(config):
1639  """Hexadecimal configuration."""
1640  return '[%s]' % ', '.join('(0x%04X, %d)' % (mode, freq)
1641  for (mode, freq) in config)
1642 
1643  def hex_fmt(size=4):
1644  """Factory for hexadecimal representation formatter."""
1645  fmt = '0x%%0%dX' % (2*size)
1646 
1647  def f(value):
1648  """Hexadecimal representation."""
1649  # length of string is twice the size of the value (in bytes)
1650  return fmt % value
1651  return f
1652 
1653  def sync_fmt(settings):
1654  """Synchronization settings: N*12 bytes"""
1655  return '[%s]' % ', '.join('(0x%02X, 0x%02X, 0x%02X, 0x%02X,'
1656  ' 0x%04X, 0x%04X, 0x%04X, 0x%04X)' % s
1657  for s in settings)
1658 
1659  def try_message(m, f, formater=None, *args, **kwargs):
1660  print ' %s ' % m,
1661  try:
1662  if formater is not None:
1663  print formater(f(*args, **kwargs))
1664  else:
1665  pprint.pprint(f(*args, **kwargs), indent=4)
1666  except MTTimeoutException as e:
1667  print 'timeout: might be unsupported by your device.'
1668  except MTErrorMessage as e:
1669  if e.code == 0x04:
1670  print 'message unsupported by your device.'
1671  else:
1672  raise e
1673  print "Device: %s at %d Bd:" % (device, baudrate)
1674  try_message("device ID:", mt.GetDeviceID, hex_fmt(4))
1675  try_message("product code:", mt.GetProductCode)
1676  try_message("firmware revision:", mt.GetFirmwareRev)
1677  try_message("baudrate:", mt.GetBaudrate)
1678  try_message("error mode:", mt.GetErrorMode, hex_fmt(2))
1679  try_message("option flags:", mt.GetOptionFlags, hex_fmt(4))
1680  try_message("location ID:", mt.GetLocationID, hex_fmt(2))
1681  try_message("transmit delay:", mt.GetTransmitDelay)
1682  try_message("synchronization settings:", mt.GetSyncSettings, sync_fmt)
1683  try_message("general configuration:", mt.GetConfiguration)
1684  try_message("output configuration (mark IV devices):",
1685  mt.GetOutputConfiguration, config_fmt)
1686  try_message("string output type:", mt.GetStringOutputType)
1687  try_message("period:", mt.GetPeriod)
1688  try_message("alignment rotation sensor:", mt.GetAlignmentRotation,
1689  parameter=0)
1690  try_message("alignment rotation local:", mt.GetAlignmentRotation,
1691  parameter=1)
1692  try_message("output mode:", mt.GetOutputMode, hex_fmt(2))
1693  try_message("extended output mode:", mt.GetExtOutputMode, hex_fmt(2))
1694  try_message("output settings:", mt.GetOutputSettings, hex_fmt(4))
1695  try_message("GPS coordinates (lat, lon, alt):", mt.GetLatLonAlt)
1696  try_message("available scenarios:", mt.GetAvailableScenarios)
1697  try_message("current scenario ID:", mt.GetCurrentScenario)
1698  try_message("UTC time:", mt.GetUTCTime)
1699 
1700 
1701 def get_output_config(config_arg):
1702  """Parse the mark IV output configuration argument."""
1703  # code and max frequency
1704  code_dict = {
1705  'tt': (0x0810, 1),
1706  'iu': (0x1010, 2000),
1707  'ip': (0x1020, 2000),
1708  'ii': (0x1030, 2000),
1709  'if': (0x1060, 2000),
1710  'ic': (0x1070, 2000),
1711  'ir': (0x1080, 2000),
1712  'oq': (0x2010, 400),
1713  'om': (0x2020, 400),
1714  'oe': (0x2030, 400),
1715  'bp': (0x3010, 50),
1716  'ad': (0x4010, 2000),
1717  'aa': (0x4020, 2000),
1718  'af': (0x4030, 2000),
1719  'ah': (0x4040, 1000),
1720  'pa': (0x5020, 400),
1721  'pp': (0x5030, 400),
1722  'pl': (0x5040, 400),
1723  'np': (0x7010, 4),
1724  'ns': (0x7020, 4),
1725  'wr': (0x8020, 2000),
1726  'wd': (0x8030, 2000),
1727  'wh': (0x8040, 1000),
1728  'gd': (0x8830, 4),
1729  'gs': (0x8840, 4),
1730  'gu': (0x8880, 4),
1731  'gi': (0x88A0, 4),
1732  'rr': (0xA010, 2000),
1733  'rt': (0xA020, 2000),
1734  'mf': (0xC020, 100),
1735  'vv': (0xD010, 400),
1736  'sb': (0xE010, 2000),
1737  'sw': (0xE020, 2000)
1738  }
1739  # format flags
1740  format_dict = {'f': 0x00, 'd': 0x03, 'e': 0x00, 'n': 0x04, 'w': 0x08}
1741  config_re = re.compile('([a-z]{2})(\d+)?([fdenw])?([fdnew])?')
1742  output_configuration = []
1743  try:
1744  for item in config_arg.split(','):
1745  group, frequency, fmt1, fmt2 = config_re.findall(item.lower())[0]
1746  code, max_freq = code_dict[group]
1747  if fmt1 in format_dict:
1748  code |= format_dict[fmt1]
1749  if fmt2 in format_dict:
1750  code |= format_dict[fmt2]
1751  if frequency:
1752  frequency = min(max_freq, int(frequency))
1753  else:
1754  frequency = max_freq
1755  output_configuration.append((code, frequency))
1756  return output_configuration
1757  except (IndexError, KeyError):
1758  print 'could not parse output specification "%s"' % item
1759  return
1760 
1761 
1762 def get_mode(arg):
1763  """Parse command line output-mode argument."""
1764  try: # decimal
1765  mode = int(arg)
1766  return mode
1767  except ValueError:
1768  pass
1769  if arg[0] == '0':
1770  try: # binary
1771  mode = int(arg, 2)
1772  return mode
1773  except ValueError:
1774  pass
1775  try: # hexadecimal
1776  mode = int(arg, 16)
1777  return mode
1778  except ValueError:
1779  pass
1780  # string mode specification
1781  mode = 0
1782  for c in arg:
1783  if c == 't':
1784  mode |= OutputMode.Temp
1785  elif c == 'c':
1786  mode |= OutputMode.Calib
1787  elif c == 'o':
1788  mode |= OutputMode.Orient
1789  elif c == 'a':
1790  mode |= OutputMode.Auxiliary
1791  elif c == 'p':
1792  mode |= OutputMode.Position
1793  elif c == 'v':
1794  mode |= OutputMode.Velocity
1795  elif c == 's':
1796  mode |= OutputMode.Status
1797  elif c == 'g':
1798  mode |= OutputMode.RAWGPS
1799  elif c == 'r':
1800  mode |= OutputMode.RAW
1801  else:
1802  print "Unknown output-mode specifier: '%s'" % c
1803  return
1804  return mode
1805 
1806 
1807 def get_settings(arg):
1808  """Parse command line output-settings argument."""
1809  try: # decimal
1810  settings = int(arg)
1811  return settings
1812  except ValueError:
1813  pass
1814  if arg[0] == '0':
1815  try: # binary
1816  settings = int(arg, 2)
1817  return settings
1818  except ValueError:
1819  pass
1820  try: # hexadecimal
1821  settings = int(arg, 16)
1822  return settings
1823  except ValueError:
1824  pass
1825  # strings settings specification
1826  timestamp = 0
1827  orient_mode = 0
1828  calib_mode = OutputSettings.CalibMode_Mask
1829  NED = 0
1830  for c in arg:
1831  if c == 't':
1832  timestamp = OutputSettings.Timestamp_SampleCnt
1833  elif c == 'n':
1834  timestamp = OutputSettings.Timestamp_None
1835  elif c == 'u':
1836  timestamp |= OutputSettings.Timestamp_UTCTime
1837  elif c == 'q':
1838  orient_mode = OutputSettings.OrientMode_Quaternion
1839  elif c == 'e':
1840  orient_mode = OutputSettings.OrientMode_Euler
1841  elif c == 'm':
1842  orient_mode = OutputSettings.OrientMode_Matrix
1843  elif c == 'A':
1844  calib_mode &= OutputSettings.CalibMode_Acc
1845  elif c == 'G':
1846  calib_mode &= OutputSettings.CalibMode_Gyr
1847  elif c == 'M':
1848  calib_mode &= OutputSettings.CalibMode_Mag
1849  elif c == 'i':
1850  calib_mode &= OutputSettings.AuxiliaryMode_NoAIN2
1851  elif c == 'j':
1852  calib_mode &= OutputSettings.AuxiliaryMode_NoAIN1
1853  elif c == 'N':
1854  NED = OutputSettings.Coordinates_NED
1855  else:
1856  print "Unknown output-settings specifier: '%s'" % c
1857  return
1858  settings = timestamp | orient_mode | calib_mode | NED
1859  return settings
1860 
1862  """Parse command line synchronization-settings argument."""
1863  if arg == "clear":
1864  sync_settings = [0,0,0,0,0,0,0,0]
1865  return sync_settings
1866  else:
1867  # Parse each field from the argument
1868  sync_settings = arg.split(',')
1869  try:
1870  # convert string to int
1871  sync_settings = tuple([int(i) for i in sync_settings])
1872  except ValueError:
1873  print "Synchronization sync_settings must be integers."
1874  return
1875  # check synchronization sync_settings
1876  if sync_settings[0] in (3, 4, 8, 9, 11) and \
1877  sync_settings[1] in (0, 1, 2, 4, 5, 6) and \
1878  sync_settings[2] in (1, 2, 3) and \
1879  sync_settings[3] in (0, 1):
1880  return sync_settings
1881  else:
1882  print "Invalid synchronization settings."
1883  return
1884 
1885 
1886 def get_UTCtime(arg):
1887  # If argument is now, fill the time settings with the current time
1888  # else fill the time settings with the specified time
1889  if arg == "now":
1890  timestamp = datetime.datetime.utcnow() # use datetime to get microsecond
1891  time_settings = []
1892  time_settings.append(timestamp.year)
1893  time_settings.append(timestamp.month)
1894  time_settings.append(timestamp.day)
1895  time_settings.append(timestamp.hour)
1896  time_settings.append(timestamp.minute)
1897  time_settings.append(timestamp.second)
1898  time_settings.append(timestamp.microsecond*1000) # multiply by 1000 to obtain nanoseconds
1899  time_settings.append(0) # default flag to 0
1900  return time_settings
1901  else:
1902  # Parse each field from the argument
1903  time_settings = arg.split(',')
1904  try:
1905  time_settings = [int(i) for i in time_settings]
1906  except ValueError:
1907  print "UTCtime settings must be integers."
1908  return
1909 
1910  # check UTCtime settings
1911  if 1999 <= time_settings[0] <= 2099 and\
1912  1 <= time_settings[1] <= 12 and\
1913  1 <= time_settings[2] <= 31 and\
1914  0 <= time_settings[3] <= 23 and\
1915  0 <= time_settings[4] <= 59 and\
1916  0 <= time_settings[5] <= 59 and\
1917  0 <= time_settings[6] <= 1000000000:
1918  return time_settings
1919  else:
1920  print "Invalid UTCtime settings."
1921  return
1922 
1923 
1924 if __name__ == '__main__':
1925  main()
def SetPeriod(self, period)
Definition: mtdevice.py:413
def GetOptionFlags(self)
Definition: mtdevice.py:289
def waitfor(self, size=1)
Definition: mtdevice.py:82
def GetOutputConfiguration(self)
Definition: mtdevice.py:378
def GetFirmwareRev(self)
Definition: mtdevice.py:234
def GetUTCTime(self)
Definition: mtdevice.py:585
def AdjustUTCTime(self, ticks)
Definition: mtdevice.py:600
def getMIDName(mid)
Definition: mtdef.py:166
def parse_MTData(self, data, mode=None, settings=None)
Definition: mtdevice.py:978
def GetOutputSettings(self)
Definition: mtdevice.py:478
def GetErrorMode(self)
Definition: mtdevice.py:265
def GoToConfig(self)
Definition: mtdevice.py:210
def get_mode(arg)
Definition: mtdevice.py:1762
def read_data_msg(self, buf=bytearray())
Definition: mtdevice.py:94
def ResetOrientation(self, code)
Definition: mtdevice.py:568
def _ensure_config_state(self)
Definition: mtdevice.py:181
def GetConfiguration(self)
Definition: mtdevice.py:349
def SetBaudrate(self, brid)
Definition: mtdevice.py:260
def SetUTCTime(self, ns, year, month, day, hour, minute, second, flag)
Definition: mtdevice.py:593
def GetSyncSettings(self)
Definition: mtdevice.py:334
def SetSyncSettings(self, sync_settings)
Definition: mtdevice.py:342
def get_settings(arg)
Definition: mtdevice.py:1807
def SetNoRotation(self, duration)
Definition: mtdevice.py:579
def auto_config_legacy(self)
Definition: mtdevice.py:632
def SetOutputSkipFactor(self, skipfactor)
Definition: mtdevice.py:492
def SetOutputConfiguration(self, output_configuration)
Definition: mtdevice.py:386
def ReqDataLength(self)
Definition: mtdevice.py:498
def write_ack(self, mid, data=b'', n_retries=500)
Definition: mtdevice.py:165
def read_measurement(self, mode=None, settings=None)
Definition: mtdevice.py:637
def get_output_config(config_arg)
Definition: mtdevice.py:1701
def find_baudrate(port, timeout=0.002, verbose=False, initial_wait=0.1)
Auto detect baudrate.
Definition: mtdevice.py:1135
def RunSelfTest(self)
Definition: mtdevice.py:243
def SetOutputMode(self, mode)
Definition: mtdevice.py:458
def SetExtOutputMode(self, ext_mode)
Definition: mtdevice.py:472
def RestoreFactoryDefaults(self)
Definition: mtdevice.py:315
def GetStringOutputType(self)
Definition: mtdevice.py:393
def GetProductCode(self)
Definition: mtdevice.py:228
def SetOptionFlags(self, set_flags, clear_flags)
Definition: mtdevice.py:296
def SetTransmitDelay(self, transmit_delay)
Definition: mtdevice.py:328
def GetCurrentScenario(self)
Definition: mtdevice.py:555
def main()
Main function.
Definition: mtdevice.py:1425
def read_msg(self)
Definition: mtdevice.py:131
def GetLatLonAlt(self)
Definition: mtdevice.py:516
def SetAlignmentRotation(self, parameter, quaternion)
Definition: mtdevice.py:440
def GetDeviceID(self)
Definition: mtdevice.py:221
def ChangeBaudrate(self, baudrate)
Definition: mtdevice.py:1102
def GetOutputMode(self)
Definition: mtdevice.py:451
def Reset(self, go_to_config=False)
High-level functions.
Definition: mtdevice.py:194
MTDevice class.
Definition: mtdevice.py:20
def __init__(self, port, baudrate=115200, timeout=0.002, autoconf=True, config_mode=False, verbose=False, initial_wait=0.1)
Definition: mtdevice.py:24
def write_msg(self, mid, data=b'')
Low-level communication.
Definition: mtdevice.py:60
def SetErrorMode(self, error_mode)
Definition: mtdevice.py:272
def GetTransmitDelay(self)
Definition: mtdevice.py:321
def find_devices(timeout=0.002, verbose=False, initial_wait=0.1)
Definition: mtdevice.py:1118
def GetPeriod(self)
Definition: mtdevice.py:406
def GetExtOutputMode(self)
Definition: mtdevice.py:465
def SetLocationID(self, location_id)
Definition: mtdevice.py:309
def SetLatLonAlt(self, lat, lon, alt)
Definition: mtdevice.py:531
def GoToMeasurement(self)
Definition: mtdevice.py:215
def get_UTCtime(arg)
Definition: mtdevice.py:1886
def _ensure_measurement_state(self)
Definition: mtdevice.py:186
def configure_legacy(self, mode, settings, period=None, skipfactor=None)
High-level utility functions.
Definition: mtdevice.py:609
def GetAlignmentRotation(self, parameter)
Definition: mtdevice.py:419
def inspect(mt, device, baudrate)
Definition: mtdevice.py:1636
def GetBaudrate(self)
Definition: mtdevice.py:254
def usage()
Documentation for stand alone usage.
Definition: mtdevice.py:1162
def get_synchronization_settings(arg)
Definition: mtdevice.py:1861
def SetStringOutputType(self, string_output_type)
Definition: mtdevice.py:400
def GetAvailableScenarios(self)
Definition: mtdevice.py:539
def parse_MTData2(self, data)
Definition: mtdevice.py:650
def SetCurrentScenario(self, scenario_id)
Definition: mtdevice.py:562
def SetOutputSettings(self, settings)
Definition: mtdevice.py:485
def GetLocationID(self)
Definition: mtdevice.py:302


xsens_driver
Author(s):
autogenerated on Thu Jun 6 2019 19:13:05