00001
00002 import serial
00003 import struct
00004 import sys
00005 import getopt
00006 import time
00007 import datetime
00008 import glob
00009 import re
00010 import pprint
00011
00012 from mtdef import MID, OutputMode, OutputSettings, MTException, Baudrates, \
00013 XDIGroup, getMIDName, DeviceState, DeprecatedMID, MTErrorMessage, \
00014 MTTimeoutException
00015
00016
00017
00018
00019
00020 class MTDevice(object):
00021 """XSens MT device communication object."""
00022
00023 def __init__(self, port, baudrate=115200, timeout=0.002, autoconf=True,
00024 config_mode=False, verbose=False):
00025 """Open device."""
00026 self.verbose = verbose
00027
00028 try:
00029 self.device = serial.Serial(port, baudrate, timeout=timeout,
00030 writeTimeout=timeout)
00031 except IOError:
00032
00033 self.device = serial.Serial(port, baudrate, timeout=timeout,
00034 writeTimeout=timeout, rtscts=True,
00035 dsrdtr=True)
00036 self.device.flushInput()
00037 self.device.flushOutput()
00038
00039 self.timeout = 100*timeout
00040
00041 self.state = None
00042 if autoconf:
00043 self.auto_config_legacy()
00044 else:
00045
00046 self.mode = None
00047
00048 self.settings = None
00049
00050 self.length = None
00051
00052 self.header = None
00053 if config_mode:
00054 self.GoToConfig()
00055
00056
00057
00058
00059 def write_msg(self, mid, data=b''):
00060 """Low-level message sending function."""
00061 length = len(data)
00062 if length > 254:
00063 lendat = b'\xFF' + struct.pack('!H', length)
00064 else:
00065 lendat = struct.pack('!B', length)
00066 packet = b'\xFA\xFF' + struct.pack('!B', mid) + lendat + data
00067 packet += struct.pack('!B', 0xFF & (-(sum(map(ord, packet[1:])))))
00068 msg = packet
00069 start = time.time()
00070 while ((time.time()-start) < self.timeout) and self.device.read():
00071 pass
00072 self.device.write(msg)
00073 if self.verbose:
00074 print "MT: Write message id 0x%02X (%s) with %d data bytes: [%s]" %\
00075 (mid, getMIDName(mid), length,
00076 ' '.join("%02X" % ord(v) for v in data))
00077
00078 def waitfor(self, size=1):
00079 """Get a given amount of data."""
00080 buf = bytearray()
00081 for _ in range(100):
00082 buf.extend(self.device.read(size-len(buf)))
00083 if len(buf) == size:
00084 return buf
00085 if self.verbose:
00086 print "waiting for %d bytes, got %d so far: [%s]" % \
00087 (size, len(buf), ' '.join('%02X' % v for v in buf))
00088 raise MTTimeoutException("waiting for message")
00089
00090 def read_data_msg(self, buf=bytearray()):
00091 """Low-level MTData receiving function.
00092 Take advantage of known message length.
00093 """
00094 start = time.time()
00095 if self.length <= 254:
00096 totlength = 5 + self.length
00097 else:
00098 totlength = 7 + self.length
00099 while (time.time()-start) < self.timeout:
00100 buf.extend(self.waitfor(totlength - len(buf)))
00101 preamble_ind = buf.find(self.header)
00102 if preamble_ind == -1:
00103
00104 if self.verbose:
00105 sys.stderr.write("MT: discarding (no preamble).\n")
00106 del buf[:-3]
00107 continue
00108 elif preamble_ind:
00109
00110 if self.verbose:
00111 sys.stderr.write("MT: discarding (before preamble).\n")
00112 del buf[:preamble_ind]
00113
00114 buf.extend(self.waitfor(totlength-len(buf)))
00115 if 0xFF & sum(buf[1:]):
00116 if self.verbose:
00117 sys.stderr.write("MT: invalid checksum; discarding data and"
00118 " waiting for next message.\n")
00119 del buf[:buf.find(self.header)-2]
00120 continue
00121 data = str(buf[-self.length-1:-1])
00122 del buf[:]
00123 return data
00124 else:
00125 raise MTException("could not find MTData message.")
00126
00127 def read_msg(self):
00128 """Low-level message receiving function."""
00129 start = time.time()
00130 while (time.time()-start) < self.timeout:
00131
00132 if ord(self.waitfor()) != 0xFA:
00133 continue
00134
00135 if ord(self.waitfor()) != 0xFF:
00136 continue
00137
00138 mid, length = struct.unpack('!BB', self.waitfor(2))
00139 if length == 255:
00140 length, = struct.unpack('!H', self.waitfor(2))
00141
00142 buf = self.waitfor(length+1)
00143 checksum = buf[-1]
00144 data = struct.unpack('!%dB' % length, buf[:-1])
00145
00146 if 0xFF & sum(data, 0xFF+mid+length+checksum):
00147 if self.verbose:
00148 sys.stderr.write("invalid checksum; discarding data and "
00149 "waiting for next message.\n")
00150 continue
00151 if self.verbose:
00152 print "MT: Got message id 0x%02X (%s) with %d data bytes: [%s]"\
00153 % (mid, getMIDName(mid), length,
00154 ' '.join("%02X" % v for v in data))
00155 if mid == MID.Error:
00156 raise MTErrorMessage(data[0])
00157 return (mid, buf[:-1])
00158 else:
00159 raise MTException("could not find message.")
00160
00161 def write_ack(self, mid, data=b'', n_retries=500):
00162 """Send a message and read confirmation."""
00163 self.write_msg(mid, data)
00164 for _ in range(n_retries):
00165 mid_ack, data_ack = self.read_msg()
00166 if mid_ack == (mid+1):
00167 break
00168 elif self.verbose:
00169 print "ack (0x%02X) expected, got 0x%02X instead" % \
00170 (mid+1, mid_ack)
00171 else:
00172 raise MTException("Ack (0x%02X) expected, MID 0x%02X received "
00173 "instead (after %d retries)." % (mid+1, mid_ack,
00174 n_retries))
00175 return data_ack
00176
00177 def _ensure_config_state(self):
00178 """Switch device to config state if necessary."""
00179 if self.state != DeviceState.Config:
00180 self.GoToConfig()
00181
00182 def _ensure_measurement_state(self):
00183 """Switch device to measurement state if necessary."""
00184 if self.state != DeviceState.Measurement:
00185 self.GoToMeasurement()
00186
00187
00188
00189
00190 def Reset(self, go_to_config=False):
00191 """Reset MT device.
00192
00193 If go_to_config then send WakeUpAck in order to leave the device in
00194 config mode.
00195 """
00196 self.write_ack(MID.Reset)
00197 if go_to_config:
00198 time.sleep(0.01)
00199 mid, _ = self.read_msg()
00200 if mid == MID.WakeUp:
00201 self.write_msg(MID.WakeUpAck)
00202 self.state = DeviceState.Config
00203 else:
00204 self.state = DeviceState.Measurement
00205
00206 def GoToConfig(self):
00207 """Place MT device in configuration mode."""
00208 self.write_ack(MID.GoToConfig)
00209 self.state = DeviceState.Config
00210
00211 def GoToMeasurement(self):
00212 """Place MT device in measurement mode."""
00213 self._ensure_config_state()
00214 self.write_ack(MID.GoToMeasurement)
00215 self.state = DeviceState.Measurement
00216
00217 def GetDeviceID(self):
00218 """Get the device identifier."""
00219 self._ensure_config_state()
00220 data = self.write_ack(MID.ReqDID)
00221 deviceID, = struct.unpack('!I', data)
00222 return deviceID
00223
00224 def GetProductCode(self):
00225 """Get the product code."""
00226 self._ensure_config_state()
00227 data = self.write_ack(MID.ReqProductCode)
00228 return str(data).strip()
00229
00230 def GetFirmwareRev(self):
00231 """Get the firmware version."""
00232 self._ensure_config_state()
00233 data = self.write_ack(MID.ReqFWRev)
00234
00235
00236 major, minor, revision = struct.unpack('!BBB', data[:3])
00237 return (major, minor, revision)
00238
00239 def RunSelfTest(self):
00240 """Run the built-in self test."""
00241 self._ensure_config_state()
00242 data = self.write_ack(MID.RunSelfTest)
00243 bit_names = ['accX', 'accY', 'accZ', 'gyrX', 'gyrY', 'gyrZ',
00244 'magX', 'magY', 'magZ']
00245 self_test_results = []
00246 for i, name in enumerate(bit_names):
00247 self_test_results.append((name, (data >> i) & 1))
00248 return self_test_results
00249
00250 def GetBaudrate(self):
00251 """Get the current baudrate id of the device."""
00252 self._ensure_config_state()
00253 data = self.write_ack(MID.SetBaudrate)
00254 return data[0]
00255
00256 def SetBaudrate(self, brid):
00257 """Set the baudrate of the device using the baudrate id."""
00258 self._ensure_config_state()
00259 self.write_ack(MID.SetBaudrate, (brid,))
00260
00261 def GetErrorMode(self):
00262 """Get the current error mode of the device."""
00263 self._ensure_config_state()
00264 data = self.write_ack(MID.SetErrorMode)
00265 error_mode, = struct.unpack('!H', data)
00266 return error_mode
00267
00268 def SetErrorMode(self, error_mode):
00269 """Set the error mode of the device.
00270
00271 The error mode defines the way the device deals with errors (expect
00272 message errors):
00273 0x0000: ignore any errors except message handling errors,
00274 0x0001: in case of missing sampling instance: increase sample
00275 counter and do not send error message,
00276 0x0002: in case of missing sampling instance: increase sample
00277 counter and send error message,
00278 0x0003: in case of non-message handling error, an error message is
00279 sent and the device will go into Config State.
00280 """
00281 self._ensure_config_state()
00282 data = struct.pack('!H', error_mode)
00283 self.write_ack(MID.SetErrorMode, data)
00284
00285 def GetOptionFlags(self):
00286 """Get the option flags (MTi-1 series)."""
00287 self._ensure_config_state()
00288 data = self.write_ack(MID.SetOptionFlags)
00289 flags, = struct.unpack('!I', data)
00290 return flags
00291
00292 def SetOptionFlags(self, set_flags, clear_flags):
00293 """Set the option flags (MTi-1 series)."""
00294 self._ensure_config_state()
00295 data = struct.pack('!II', set_flags, clear_flags)
00296 self.write_ack(MID.SetOptionFlags, data)
00297
00298 def GetLocationID(self):
00299 """Get the location ID of the device."""
00300 self._ensure_config_state()
00301 data = self.write_ack(MID.SetLocationID)
00302 location_id, = struct.unpack('!H', data)
00303 return location_id
00304
00305 def SetLocationID(self, location_id):
00306 """Set the location ID of the device (arbitrary)."""
00307 self._ensure_config_state()
00308 data = struct.pack('!H', location_id)
00309 self.write_ack(MID.SetLocationID, data)
00310
00311 def RestoreFactoryDefaults(self):
00312 """Restore MT device configuration to factory defaults (soft version).
00313 """
00314 self._ensure_config_state()
00315 self.write_ack(MID.RestoreFactoryDef)
00316
00317 def GetTransmitDelay(self):
00318 """Get the transmission delay (only RS485)."""
00319 self._ensure_config_state()
00320 data = self.write_ack(MID.SetTransmitDelay)
00321 transmit_delay, = struct.unpack('!H', data)
00322 return transmit_delay
00323
00324 def SetTransmitDelay(self, transmit_delay):
00325 """Set the transmission delay (only RS485)."""
00326 self._ensure_config_state()
00327 data = struct.pack('!H', transmit_delay)
00328 self.write_ack(MID.SetTransmitDelay, data)
00329
00330 def GetSyncSettings(self):
00331 """Get the synchronisation settings."""
00332 self._ensure_config_state()
00333 data = self.write_ack(MID.SetSyncSettings)
00334 sync_settings = [struct.unpack('!BBBBHHHH', data[o:o+12])
00335 for o in range(0, len(data), 12)]
00336 return sync_settings
00337
00338 def SetSyncSettings(self, sync_settings):
00339 """Set the synchronisation settings (mark IV)"""
00340 self._ensure_config_state()
00341 data = b''.join(struct.pack('!BBBBHHHH', *sync_setting)
00342 for sync_setting in sync_settings)
00343 self.write_ack(MID.SetSyncSettings, data)
00344
00345 def GetConfiguration(self):
00346 """Ask for the current configuration of the MT device."""
00347 self._ensure_config_state()
00348 config = self.write_ack(MID.ReqConfiguration)
00349 try:
00350 masterID, period, skipfactor, _, _, _, date, time, num, deviceID,\
00351 length, mode, settings =\
00352 struct.unpack('!IHHHHI8s8s32x32xHIHHI8x', config)
00353 except struct.error:
00354 raise MTException("could not parse configuration.")
00355 self.mode = mode
00356 self.settings = settings
00357 self.length = length
00358 if self.length <= 254:
00359 self.header = b'\xFA\xFF\x32' + struct.pack('!B', self.length)
00360 else:
00361 self.header = b'\xFA\xFF\x32\xFF' + struct.pack('!H', self.length)
00362 conf = {'output-mode': mode,
00363 'output-settings': settings,
00364 'length': length,
00365 'period': period,
00366 'skipfactor': skipfactor,
00367 'Master device ID': masterID,
00368 'date': date,
00369 'time': time,
00370 'number of devices': num,
00371 'device ID': deviceID}
00372 return conf
00373
00374 def GetOutputConfiguration(self):
00375 """Get the output configuration of the device (mark IV)."""
00376 self._ensure_config_state()
00377 data = self.write_ack(MID.SetOutputConfiguration)
00378 output_configuration = [struct.unpack('!HH', data[o:o+4])
00379 for o in range(0, len(data), 4)]
00380 return output_configuration
00381
00382 def SetOutputConfiguration(self, output_configuration):
00383 """Set the output configuration of the device (mark IV)."""
00384 self._ensure_config_state()
00385 data = b''.join(struct.pack('!HH', *output)
00386 for output in output_configuration)
00387 self.write_ack(MID.SetOutputConfiguration, data)
00388
00389 def GetStringOutputType(self):
00390 """Get the NMEA data output configuration."""
00391 self._ensure_config_state()
00392 data = self.write_ack(MID.SetStringOutputType)
00393 string_output_type, = struct.unpack('!H', data)
00394 return string_output_type
00395
00396 def SetStringOutputType(self, string_output_type):
00397 """Set the configuration of the NMEA data output."""
00398 self._ensure_config_state()
00399 data = struct.pack('!H', string_output_type)
00400 self.write_ack(MID.SetStringOutputType, data)
00401
00402 def GetPeriod(self):
00403 """Get the sampling period."""
00404 self._ensure_config_state()
00405 data = self.write_ack(MID.SetPeriod)
00406 period, = struct.unpack('!H', data)
00407 return period
00408
00409 def SetPeriod(self, period):
00410 """Set the sampling period."""
00411 self._ensure_config_state()
00412 data = struct.pack('!H', period)
00413 self.write_ack(MID.SetPeriod, data)
00414
00415 def GetAlignmentRotation(self, parameter):
00416 """Get the object alignment.
00417
00418 parameter indicates the desired alignment quaternion:
00419 0 for sensor alignment (RotSensor),
00420 1 for local alignment (RotLocal).
00421 """
00422 self._ensure_config_state()
00423 data = struct.pack('!B', parameter)
00424 data = self.write_ack(MID.SetAlignmentRotation, data)
00425 q0, q1, q2, q3 = struct.unpack('!ffff', data)
00426 return q0, q1, q2, q3
00427
00428 def SetAlignmentRotation(self, parameter, quaternion):
00429 """Set the object alignment.
00430
00431 parameter indicates the desired alignment quaternion:
00432 0 for sensor alignment (RotSensor),
00433 1 for local alignment (RotLocal).
00434 """
00435 self._ensure_config_state()
00436 data = struct.pack('!Bffff', parameter, *quaternion)
00437 self.write_ack(MID.SetAlignmentRotation, data)
00438
00439 def GetOutputMode(self):
00440 """Get current output mode."""
00441 self._ensure_config_state()
00442 data = self.write_ack(MID.SetOutputMode)
00443 self.mode, = struct.unpack('!H', data)
00444 return self.mode
00445
00446 def SetOutputMode(self, mode):
00447 """Select which information to output."""
00448 self._ensure_config_state()
00449 data = struct.pack('!H', mode)
00450 self.write_ack(MID.SetOutputMode, data)
00451 self.mode = mode
00452
00453 def GetExtOutputMode(self):
00454 """Get current extended output mode (for alternative UART)."""
00455 self._ensure_config_state()
00456 data = self.write_ack(MID.SetExtOutputMode)
00457 ext_mode, = struct.unpack('!H', data)
00458 return ext_mode
00459
00460 def SetExtOutputMode(self, ext_mode):
00461 """Set extended output mode (for alternative UART)."""
00462 self._ensure_config_state()
00463 data = struct.pack('!H', ext_mode)
00464 self.write_ack(MID.SetExtOutputMode, data)
00465
00466 def GetOutputSettings(self):
00467 """Get current output mode."""
00468 self._ensure_config_state()
00469 data = self.write_ack(MID.SetOutputSettings)
00470 self.settings, = struct.unpack('!I', data)
00471 return self.settings
00472
00473 def SetOutputSettings(self, settings):
00474 """Select how to output the information."""
00475 self._ensure_config_state()
00476 data = struct.pack('!I', settings)
00477 self.write_ack(MID.SetOutputSettings, data)
00478 self.settings = settings
00479
00480 def SetOutputSkipFactor(self, skipfactor):
00481 """Set the output skip factor."""
00482 self._ensure_config_state()
00483 data = struct.pack('!H', skipfactor)
00484 self.write_ack(DeprecatedMID.SetOutputSkipFactor, data)
00485
00486 def ReqDataLength(self):
00487 """Get data length for mark III devices."""
00488 self._ensure_config_state()
00489 try:
00490 data = self.write_ack(DeprecatedMID.ReqDataLength)
00491 except MTErrorMessage as e:
00492 if e.code == 0x04:
00493 sys.stderr.write("ReqDataLength message is deprecated and not "
00494 "recognised by your device.")
00495 return
00496 raise e
00497 self.length, = struct.unpack('!H', data)
00498 if self.length <= 254:
00499 self.header = b'\xFA\xFF\x32' + struct.pack('!B', self.length)
00500 else:
00501 self.header = b'\xFA\xFF\x32\xFF' + struct.pack('!H', self.length)
00502 return self.length
00503
00504 def GetLatLonAlt(self):
00505 """Get the stored position of the device.
00506 It is used internally for local magnetic declination and local gravity.
00507 """
00508 self._ensure_config_state()
00509 data = self.write_ack(MID.SetLatLonAlt)
00510 if len(data) == 24:
00511 lat, lon, alt = struct.unpack('!ddd', data)
00512 elif len(data) == 12:
00513 lat, lon, alt = struct.unpack('!fff', data)
00514 else:
00515 raise MTException('Could not parse ReqLatLonAltAck message: wrong'
00516 'size of message.')
00517 return (lat, lon, alt)
00518
00519 def SetLatLonAlt(self, lat, lon, alt):
00520 """Set the position of the device.
00521 It is used internally for local magnetic declination and local gravity.
00522 """
00523 self._ensure_config_state()
00524 data = struct.pack('!ddd', lat, lon, alt)
00525 self.write_ack(MID.SetLatLonAlt, data)
00526
00527 def GetAvailableScenarios(self):
00528 """Get the available XKF scenarios on the device."""
00529 self._ensure_config_state()
00530 data = self.write_ack(MID.ReqAvailableScenarios)
00531 scenarios = []
00532 try:
00533 for i in range(len(data)/22):
00534 scenario_type, version, label =\
00535 struct.unpack('!BB20s', data[22*i:22*(i+1)])
00536 scenarios.append((scenario_type, version, label.strip()))
00537
00538 self.scenarios = scenarios
00539 except struct.error:
00540 raise MTException("could not parse the available XKF scenarios.")
00541 return scenarios
00542
00543 def GetCurrentScenario(self):
00544 """Get the ID of the currently used XKF scenario."""
00545 self._ensure_config_state()
00546 data = self.write_ack(MID.SetCurrentScenario)
00547 _, self.scenario_id = struct.unpack('!BB', data)
00548 return self.scenario_id
00549
00550 def SetCurrentScenario(self, scenario_id):
00551 """Sets the XKF scenario to use."""
00552 self._ensure_config_state()
00553 data = struct.pack('!BB', 0, scenario_id)
00554 self.write_ack(MID.SetCurrentScenario, data)
00555
00556 def ResetOrientation(self, code):
00557 """Reset the orientation.
00558
00559 Code can take several values:
00560 0x0000: store current settings (only in config mode),
00561 0x0001: heading reset (NOT supported by MTi-G),
00562 0x0003: object reset.
00563 """
00564 data = struct.pack('!H', code)
00565 self.write_ack(MID.ResetOrientation, data)
00566
00567 def SetNoRotation(self, duration):
00568 """Initiate the "no rotation" procedure to estimate gyro biases."""
00569 self._ensure_measurement_state()
00570 data = struct.pack('!H', duration)
00571 self.write_ack(MID.SetNoRotation, data)
00572
00573 def GetUTCTime(self):
00574 """Get UTC time from device."""
00575 self._ensure_config_state()
00576 data = self.write_ack(MID.SetUTCTime)
00577 ns, year, month, day, hour, minute, second, flag = \
00578 struct.unpack('!IHBBBBBB', data)
00579 return (ns, year, month, day, hour, minute, second, flag)
00580
00581 def SetUTCTime(self, ns, year, month, day, hour, minute, second, flag):
00582 """Set UTC time on the device."""
00583 self._ensure_config_state()
00584 data = struct.pack('!IHBBBBBB', ns, year, month, day, hour, minute,
00585 second, flag)
00586 self.write_ack(MID.SetUTCTime, data)
00587
00588 def AdjustUTCTime(self, ticks):
00589 """Adjust UTC Time of device using correction ticks (0.1 ms)."""
00590 self._ensure_config_state()
00591 data = struct.pack('!i', ticks)
00592 self.write(MID.AdjustUTCTime, data)
00593
00594
00595
00596
00597 def configure_legacy(self, mode, settings, period=None, skipfactor=None):
00598 """Configure the mode and settings of the MT device in legacy mode."""
00599 try:
00600
00601 self.SetOutputConfiguration([(0x0000, 0)])
00602 except MTErrorMessage as e:
00603 if e.code == 0x04:
00604
00605 pass
00606 else:
00607 raise
00608 except MTException as e:
00609 if self.verbose:
00610 print "no ack received while switching from MTData2 to MTData."
00611 pass
00612 self.SetOutputMode(mode)
00613 self.SetOutputSettings(settings)
00614 if period is not None:
00615 self.SetPeriod(period)
00616 if skipfactor is not None:
00617 self.SetOutputSkipFactor(skipfactor)
00618 self.GetConfiguration()
00619
00620 def auto_config_legacy(self):
00621 """Read configuration from device in legacy mode."""
00622 self.GetConfiguration()
00623 return self.mode, self.settings, self.length
00624
00625 def read_measurement(self, mode=None, settings=None):
00626 self._ensure_measurement_state()
00627
00628
00629 mid, data = self.read_msg()
00630 if mid == MID.MTData:
00631 return self.parse_MTData(data, mode, settings)
00632 elif mid == MID.MTData2:
00633 return self.parse_MTData2(data)
00634 else:
00635 raise MTException("unknown data message: mid=0x%02X (%s)." %
00636 (mid, getMIDName(mid)))
00637
00638 def parse_MTData2(self, data):
00639
00640 def parse_temperature(data_id, content, ffmt):
00641 o = {}
00642 if (data_id & 0x00F0) == 0x10:
00643 o['Temp'], = struct.unpack('!'+ffmt, content)
00644 else:
00645 raise MTException("unknown packet: 0x%04X." % data_id)
00646 return o
00647
00648 def parse_timestamp(data_id, content, ffmt):
00649 o = {}
00650 if (data_id & 0x00F0) == 0x10:
00651 o['ns'], o['Year'], o['Month'], o['Day'], o['Hour'],\
00652 o['Minute'], o['Second'], o['Flags'] =\
00653 struct.unpack('!LHBBBBBB', content)
00654 elif (data_id & 0x00F0) == 0x20:
00655 o['PacketCounter'], = struct.unpack('!H', content)
00656 elif (data_id & 0x00F0) == 0x30:
00657 o['TimeOfWeek'], = struct.unpack('!L', content)
00658 elif (data_id & 0x00F0) == 0x40:
00659 o['gpsAge'], = struct.unpack('!B', content)
00660 elif (data_id & 0x00F0) == 0x50:
00661 o['pressureAge'], = struct.unpack('!B', content)
00662 elif (data_id & 0x00F0) == 0x60:
00663 o['SampleTimeFine'], = struct.unpack('!L', content)
00664 elif (data_id & 0x00F0) == 0x70:
00665 o['SampleTimeCoarse'], = struct.unpack('!L', content)
00666 elif (data_id & 0x00F0) == 0x80:
00667 o['startFrame'], o['endFrame'] = struct.unpack('!HH', content)
00668 else:
00669 raise MTException("unknown packet: 0x%04X." % data_id)
00670 return o
00671
00672 def parse_orientation_data(data_id, content, ffmt):
00673 o = {}
00674 if (data_id & 0x000C) == 0x00:
00675 o['frame'] = 'ENU'
00676 elif (data_id & 0x000C) == 0x04:
00677 o['frame'] = 'NED'
00678 elif (data_id & 0x000C) == 0x08:
00679 o['frame'] = 'NWU'
00680 if (data_id & 0x00F0) == 0x10:
00681 o['Q0'], o['Q1'], o['Q2'], o['Q3'] = struct.unpack('!'+4*ffmt,
00682 content)
00683 elif (data_id & 0x00F0) == 0x20:
00684 o['a'], o['b'], o['c'], o['d'], o['e'], o['f'], o['g'], o['h'],\
00685 o['i'] = struct.unpack('!'+9*ffmt, content)
00686 elif (data_id & 0x00F0) == 0x30:
00687 o['Roll'], o['Pitch'], o['Yaw'] = struct.unpack('!'+3*ffmt,
00688 content)
00689 else:
00690 raise MTException("unknown packet: 0x%04X." % data_id)
00691 return o
00692
00693 def parse_pressure(data_id, content, ffmt):
00694 o = {}
00695 if (data_id & 0x00F0) == 0x10:
00696 o['Pressure'], = struct.unpack('!L', content)
00697 else:
00698 raise MTException("unknown packet: 0x%04X." % data_id)
00699 return o
00700
00701 def parse_acceleration(data_id, content, ffmt):
00702 o = {}
00703 if (data_id & 0x000C) == 0x00:
00704 o['frame'] = 'ENU'
00705 elif (data_id & 0x000C) == 0x04:
00706 o['frame'] = 'NED'
00707 elif (data_id & 0x000C) == 0x08:
00708 o['frame'] = 'NWU'
00709 if (data_id & 0x00F0) == 0x10:
00710 o['Delta v.x'], o['Delta v.y'], o['Delta v.z'] = \
00711 struct.unpack('!'+3*ffmt, content)
00712 elif (data_id & 0x00F0) == 0x20:
00713 o['accX'], o['accY'], o['accZ'] = \
00714 struct.unpack('!'+3*ffmt, content)
00715 elif (data_id & 0x00F0) == 0x30:
00716 o['freeAccX'], o['freeAccY'], o['freeAccZ'] = \
00717 struct.unpack('!'+3*ffmt, content)
00718 elif (data_id & 0x00F0) == 0x40:
00719 o['accX'], o['accY'], o['accZ'] = \
00720 struct.unpack('!'+3*ffmt, content)
00721 else:
00722 raise MTException("unknown packet: 0x%04X." % data_id)
00723 return o
00724
00725 def parse_position(data_id, content, ffmt):
00726 o = {}
00727 if (data_id & 0x000C) == 0x00:
00728 o['frame'] = 'ENU'
00729 elif (data_id & 0x000C) == 0x04:
00730 o['frame'] = 'NED'
00731 elif (data_id & 0x000C) == 0x08:
00732 o['frame'] = 'NWU'
00733 if (data_id & 0x00F0) == 0x10:
00734 o['altMsl'], = struct.unpack('!'+ffmt, content)
00735 elif (data_id & 0x00F0) == 0x20:
00736 o['altEllipsoid'], = struct.unpack('!'+ffmt, content)
00737 elif (data_id & 0x00F0) == 0x30:
00738 o['ecefX'], o['ecefY'], o['ecefZ'] = \
00739 struct.unpack('!'+3*ffmt, content)
00740 elif (data_id & 0x00F0) == 0x40:
00741 o['lat'], o['lon'] = struct.unpack('!'+2*ffmt, content)
00742 else:
00743 raise MTException("unknown packet: 0x%04X." % data_id)
00744 return o
00745
00746 def parse_GNSS(data_id, content, ffmt):
00747 o = {}
00748 if (data_id & 0x00F0) == 0x10:
00749 o['itow'], o['year'], o['month'], o['day'], o['hour'],\
00750 o['min'], o['sec'], o['valid'], o['tAcc'], o['nano'],\
00751 o['fixtype'], o['flags'], o['numSV'], o['lon'], o['lat'],\
00752 o['height'], o['hMSL'], o['hAcc'], o['vAcc'], o['velN'],\
00753 o['velE'], o['velD'], o['gSpeed'], o['headMot'], o['sAcc'],\
00754 o['headAcc'], o['headVeh'], o['gdop'], o['pdop'],\
00755 o['tdop'], o['vdop'], o['hdop'], o['ndop'], o['edop'] = \
00756 struct.unpack('!IHBBBBBBIiBBBxiiiiIIiiiiiIIiHHHHHHH',
00757 content)
00758
00759 o['lon'] *= 1e-7
00760 o['lat'] *= 1e-7
00761 o['headMot'] *= 1e-5
00762 o['headVeh'] *= 1e-5
00763 o['gdop'] *= 0.01
00764 o['pdop'] *= 0.01
00765 o['tdop'] *= 0.01
00766 o['vdop'] *= 0.01
00767 o['hdop'] *= 0.01
00768 o['ndop'] *= 0.01
00769 o['edop'] *= 0.01
00770 elif (data_id & 0x00F0) == 0x20:
00771 o['iTOW'], o['numSvs'] = struct.unpack('!LBxxx', content[:8])
00772 svs = []
00773 ch = {}
00774 for i in range(o['numSvs']):
00775 ch['gnssId'], ch['svId'], ch['cno'], ch['flags'] = \
00776 struct.unpack('!BBBB', content[8+4*i:12+4*i])
00777 svs.append(ch)
00778 o['svs'] = svs
00779 else:
00780 raise MTException("unknown packet: 0x%04X." % data_id)
00781 return o
00782
00783 def parse_angular_velocity(data_id, content, ffmt):
00784 o = {}
00785 if (data_id & 0x000C) == 0x00:
00786 o['frame'] = 'ENU'
00787 elif (data_id & 0x000C) == 0x04:
00788 o['frame'] = 'NED'
00789 elif (data_id & 0x000C) == 0x08:
00790 o['frame'] = 'NWU'
00791 if (data_id & 0x00F0) == 0x20:
00792 o['gyrX'], o['gyrY'], o['gyrZ'] = \
00793 struct.unpack('!'+3*ffmt, content)
00794 elif (data_id & 0x00F0) == 0x30:
00795 o['Delta q0'], o['Delta q1'], o['Delta q2'], o['Delta q3'] = \
00796 struct.unpack('!'+4*ffmt, content)
00797 elif (data_id & 0x00F0) == 0x40:
00798 o['gyrX'], o['gyrY'], o['gyrZ'] = \
00799 struct.unpack('!'+3*ffmt, content)
00800 else:
00801 raise MTException("unknown packet: 0x%04X." % data_id)
00802 return o
00803
00804 def parse_GPS(data_id, content, ffmt):
00805 o = {}
00806 if (data_id & 0x00F0) == 0x30:
00807 o['iTOW'], g, p, t, v, h, n, e = \
00808 struct.unpack('!LHHHHHHH', content)
00809 o['gDOP'], o['pDOP'], o['tDOP'], o['vDOP'], o['hDOP'], \
00810 o['nDOP'], o['eDOP'] = 0.01*g, 0.01*p, 0.01*t, \
00811 0.01*v, 0.01*h, 0.01*n, 0.01*e
00812 elif (data_id & 0x00F0) == 0x40:
00813 o['iTOW'], o['fTOW'], o['Week'], o['gpsFix'], o['Flags'], \
00814 o['ecefX'], o['ecefY'], o['ecefZ'], o['pAcc'], \
00815 o['ecefVX'], o['ecefVY'], o['ecefVZ'], o['sAcc'], \
00816 o['pDOP'], o['numSV'] = \
00817 struct.unpack('!LlhBBlllLlllLHxBx', content)
00818
00819 o['pDOP'] *= 0.01
00820 elif (data_id & 0x00F0) == 0x80:
00821 o['iTOW'], o['tAcc'], o['nano'], o['year'], o['month'], \
00822 o['day'], o['hour'], o['min'], o['sec'], o['valid'] = \
00823 struct.unpack('!LLlHBBBBBB', content)
00824 elif (data_id & 0x00F0) == 0xA0:
00825 o['iTOW'], o['numCh'] = struct.unpack('!LBxxx', content[:8])
00826 channels = []
00827 ch = {}
00828 for i in range(o['numCh']):
00829 ch['chn'], ch['svid'], ch['flags'], ch['quality'], \
00830 ch['cno'], ch['elev'], ch['azim'], ch['prRes'] = \
00831 struct.unpack('!BBBBBbhl', content[8+12*i:20+12*i])
00832 channels.append(ch)
00833 o['channels'] = channels
00834 else:
00835 raise MTException("unknown packet: 0x%04X." % data_id)
00836 return o
00837
00838 def parse_SCR(data_id, content, ffmt):
00839 o = {}
00840 if (data_id & 0x00F0) == 0x10:
00841 o['accX'], o['accY'], o['accZ'], o['gyrX'], o['gyrY'], \
00842 o['gyrZ'], o['magX'], o['magY'], o['magZ'], o['Temp'] = \
00843 struct.unpack("!9Hh", content)
00844 elif (data_id & 0x00F0) == 0x20:
00845 o['tempGyrX'], o['tempGyrY'], o['tempGyrZ'] = \
00846 struct.unpack("!hhh", content)
00847 else:
00848 raise MTException("unknown packet: 0x%04X." % data_id)
00849 return o
00850
00851 def parse_analog_in(data_id, content, ffmt):
00852 o = {}
00853 if (data_id & 0x00F0) == 0x10:
00854 o['analogIn1'], = struct.unpack("!H", content)
00855 elif (data_id & 0x00F0) == 0x20:
00856 o['analogIn2'], = struct.unpack("!H", content)
00857 else:
00858 raise MTException("unknown packet: 0x%04X." % data_id)
00859 return o
00860
00861 def parse_magnetic(data_id, content, ffmt):
00862 o = {}
00863 if (data_id & 0x000C) == 0x00:
00864 o['frame'] = 'ENU'
00865 elif (data_id & 0x000C) == 0x04:
00866 o['frame'] = 'NED'
00867 elif (data_id & 0x000C) == 0x08:
00868 o['frame'] = 'NWU'
00869 if (data_id & 0x00F0) == 0x20:
00870 o['magX'], o['magY'], o['magZ'] = \
00871 struct.unpack("!3"+ffmt, content)
00872 else:
00873 raise MTException("unknown packet: 0x%04X." % data_id)
00874 return o
00875
00876 def parse_velocity(data_id, content, ffmt):
00877 o = {}
00878 if (data_id & 0x000C) == 0x00:
00879 o['frame'] = 'ENU'
00880 elif (data_id & 0x000C) == 0x04:
00881 o['frame'] = 'NED'
00882 elif (data_id & 0x000C) == 0x08:
00883 o['frame'] = 'NWU'
00884 if (data_id & 0x00F0) == 0x10:
00885 o['velX'], o['velY'], o['velZ'] = \
00886 struct.unpack("!3"+ffmt, content)
00887 else:
00888 raise MTException("unknown packet: 0x%04X." % data_id)
00889 return o
00890
00891 def parse_status(data_id, content, ffmt):
00892 o = {}
00893 if (data_id & 0x00F0) == 0x10:
00894 o['StatusByte'], = struct.unpack("!B", content)
00895 elif (data_id & 0x00F0) == 0x20:
00896 o['StatusWord'], = struct.unpack("!L", content)
00897 elif (data_id & 0x00F0) == 0x40:
00898 o['RSSI'], = struct.unpack("!b", content)
00899 else:
00900 raise MTException("unknown packet: 0x%04X." % data_id)
00901 return o
00902
00903
00904 output = {}
00905 while data:
00906 try:
00907 data_id, size = struct.unpack('!HB', data[:3])
00908 if (data_id & 0x0003) == 0x3:
00909 float_format = 'd'
00910 elif (data_id & 0x0003) == 0x0:
00911 float_format = 'f'
00912 else:
00913 raise MTException("fixed point precision not supported.")
00914 content = data[3:3+size]
00915 data = data[3+size:]
00916 group = data_id & 0xF800
00917 ffmt = float_format
00918 if group == XDIGroup.Temperature:
00919 output.setdefault('Temperature', {}).update(
00920 parse_temperature(data_id, content, ffmt))
00921 elif group == XDIGroup.Timestamp:
00922 output.setdefault('Timestamp', {}).update(
00923 parse_timestamp(data_id, content, ffmt))
00924 elif group == XDIGroup.OrientationData:
00925 output.setdefault('Orientation Data', {}).update(
00926 parse_orientation_data(data_id, content, ffmt))
00927 elif group == XDIGroup.Pressure:
00928 output.setdefault('Pressure', {}).update(
00929 parse_pressure(data_id, content, ffmt))
00930 elif group == XDIGroup.Acceleration:
00931 output.setdefault('Acceleration', {}).update(
00932 parse_acceleration(data_id, content, ffmt))
00933 elif group == XDIGroup.Position:
00934 output.setdefault('Position', {}).update(
00935 parse_position(data_id, content, ffmt))
00936 elif group == XDIGroup.GNSS:
00937 output.setdefault('GNSS', {}).update(
00938 parse_GNSS(data_id, content, ffmt))
00939 elif group == XDIGroup.AngularVelocity:
00940 output.setdefault('Angular Velocity', {}).update(
00941 parse_angular_velocity(data_id, content, ffmt))
00942 elif group == XDIGroup.GPS:
00943 output.setdefault('GPS', {}).update(
00944 parse_GPS(data_id, content, ffmt))
00945 elif group == XDIGroup.SensorComponentReadout:
00946 output.setdefault('SCR', {}).update(
00947 parse_SCR(data_id, content, ffmt))
00948 elif group == XDIGroup.AnalogIn:
00949 output.setdefault('Analog In', {}).update(
00950 parse_analog_in(data_id, content, ffmt))
00951 elif group == XDIGroup.Magnetic:
00952 output.setdefault('Magnetic', {}).update(
00953 parse_magnetic(data_id, content, ffmt))
00954 elif group == XDIGroup.Velocity:
00955 output.setdefault('Velocity', {}).update(
00956 parse_velocity(data_id, content, ffmt))
00957 elif group == XDIGroup.Status:
00958 output.setdefault('Status', {}).update(
00959 parse_status(data_id, content, ffmt))
00960 else:
00961 raise MTException("unknown XDI group: 0x%04X." % group)
00962 except struct.error:
00963 raise MTException("couldn't parse MTData2 message.")
00964 return output
00965
00966 def parse_MTData(self, data, mode=None, settings=None):
00967 """Read and parse a legacy measurement packet."""
00968
00969 if mode is None:
00970 mode = self.mode
00971 if settings is None:
00972 settings = self.settings
00973
00974 output = {}
00975 try:
00976
00977 if mode & OutputMode.RAW:
00978 o = {}
00979 o['accX'], o['accY'], o['accZ'], o['gyrX'], o['gyrY'], \
00980 o['gyrZ'], o['magX'], o['magY'], o['magZ'], o['temp'] =\
00981 struct.unpack('!10H', data[:20])
00982 data = data[20:]
00983 output['RAW'] = o
00984
00985 if mode & OutputMode.RAWGPS:
00986 o = {}
00987 o['Press'], o['bPrs'], o['ITOW'], o['LAT'], o['LON'], o['ALT'],\
00988 o['VEL_N'], o['VEL_E'], o['VEL_D'], o['Hacc'], o['Vacc'],\
00989 o['Sacc'], o['bGPS'] = struct.unpack('!HBI6i3IB', data[:44])
00990 data = data[44:]
00991 output['RAWGPS'] = o
00992
00993 if mode & OutputMode.Temp:
00994 temp, = struct.unpack('!f', data[:4])
00995 data = data[4:]
00996 output['Temp'] = temp
00997
00998 if mode & OutputMode.Calib:
00999 o = {}
01000 if (settings & OutputSettings.Coordinates_NED):
01001 o['frame'] = 'NED'
01002 else:
01003 o['frame'] = 'ENU'
01004 if not (settings & OutputSettings.CalibMode_GyrMag):
01005 o['accX'], o['accY'], o['accZ'] = struct.unpack('!3f',
01006 data[:12])
01007 data = data[12:]
01008 if not (settings & OutputSettings.CalibMode_AccMag):
01009 o['gyrX'], o['gyrY'], o['gyrZ'] = struct.unpack('!3f',
01010 data[:12])
01011 data = data[12:]
01012 if not (settings & OutputSettings.CalibMode_AccGyr):
01013 o['magX'], o['magY'], o['magZ'] = struct.unpack('!3f',
01014 data[:12])
01015 data = data[12:]
01016 output['Calib'] = o
01017
01018 if mode & OutputMode.Orient:
01019 o = {}
01020 if (settings & OutputSettings.Coordinates_NED):
01021 o['frame'] = 'NED'
01022 else:
01023 o['frame'] = 'ENU'
01024 if settings & OutputSettings.OrientMode_Euler:
01025 o['roll'], o['pitch'], o['yaw'] = struct.unpack('!3f',
01026 data[:12])
01027 data = data[12:]
01028 elif settings & OutputSettings.OrientMode_Matrix:
01029 a, b, c, d, e, f, g, h, i = struct.unpack('!9f',
01030 data[:36])
01031 data = data[36:]
01032 o['matrix'] = ((a, b, c), (d, e, f), (g, h, i))
01033 else:
01034 q0, q1, q2, q3 = struct.unpack('!4f', data[:16])
01035 data = data[16:]
01036 o['quaternion'] = (q0, q1, q2, q3)
01037 output['Orient'] = o
01038
01039 if mode & OutputMode.Auxiliary:
01040 o = {}
01041 if not (settings & OutputSettings.AuxiliaryMode_NoAIN1):
01042 o['Ain_1'], = struct.unpack('!H', data[:2])
01043 data = data[2:]
01044 if not (settings & OutputSettings.AuxiliaryMode_NoAIN2):
01045 o['Ain_2'], = struct.unpack('!H', data[:2])
01046 data = data[2:]
01047 output['Auxiliary'] = o
01048
01049 if mode & OutputMode.Position:
01050 o = {}
01051 o['Lat'], o['Lon'], o['Alt'] = struct.unpack('!3f', data[:12])
01052 data = data[12:]
01053 output['Pos'] = o
01054
01055 if mode & OutputMode.Velocity:
01056 o = {}
01057 if (settings & OutputSettings.Coordinates_NED):
01058 o['frame'] = 'NED'
01059 else:
01060 o['frame'] = 'ENU'
01061 o['Vel_X'], o['Vel_Y'], o['Vel_Z'] = struct.unpack('!3f',
01062 data[:12])
01063 data = data[12:]
01064 output['Vel'] = o
01065
01066 if mode & OutputMode.Status:
01067 status, = struct.unpack('!B', data[:1])
01068 data = data[1:]
01069 output['Stat'] = status
01070
01071 if settings & OutputSettings.Timestamp_SampleCnt:
01072 TS, = struct.unpack('!H', data[:2])
01073 data = data[2:]
01074 output['Sample'] = TS
01075
01076 if settings & OutputSettings.Timestamp_UTCTime:
01077 o = {}
01078 o['ns'], o['Year'], o['Month'], o['Day'], o['Hour'],\
01079 o['Minute'], o['Second'], o['Flags'] = struct.unpack(
01080 '!ihbbbbb', data[:12])
01081 data = data[12:]
01082 output['Timestamp'] = o
01083
01084 except struct.error, e:
01085 raise MTException("could not parse MTData message.")
01086 if data != '':
01087 raise MTException("could not parse MTData message (too long).")
01088 return output
01089
01090 def ChangeBaudrate(self, baudrate):
01091 """Change the baudrate, reset the device and reopen communication."""
01092 brid = Baudrates.get_BRID(baudrate)
01093 self.SetBaudrate(brid)
01094 self.Reset()
01095
01096 self.device.baudrate = baudrate
01097
01098 time.sleep(0.01)
01099 self.read_msg()
01100 self.write_msg(MID.WakeUpAck)
01101
01102
01103
01104
01105
01106 def find_devices(verbose=False):
01107 mtdev_list = []
01108 for port in glob.glob("/dev/tty*S*"):
01109 if verbose:
01110 print "Trying '%s'" % port
01111 try:
01112 br = find_baudrate(port, verbose)
01113 if br:
01114 mtdev_list.append((port, br))
01115 except MTException:
01116 pass
01117 return mtdev_list
01118
01119
01120
01121
01122
01123 def find_baudrate(port, verbose=False):
01124 baudrates = (115200, 460800, 921600, 230400, 57600, 38400, 19200, 9600)
01125 for br in baudrates:
01126 if verbose:
01127 print "Trying %d bd:" % br,
01128 sys.stdout.flush()
01129 try:
01130 mt = MTDevice(port, br, verbose=verbose)
01131 except serial.SerialException:
01132 if verbose:
01133 print "fail: unable to open device."
01134 raise MTException("unable to open %s" % port)
01135 try:
01136 mt.GoToConfig()
01137 mt.GoToMeasurement()
01138 if verbose:
01139 print "ok."
01140 return br
01141 except MTException:
01142 if verbose:
01143 print "fail."
01144
01145
01146
01147
01148
01149 def usage():
01150 print """MT device driver.
01151 Usage:
01152 ./mtdevice.py [commands] [opts]
01153
01154 Commands:
01155 -h, --help
01156 Print this help and quit.
01157 -r, --reset
01158 Reset device to factory defaults.
01159 -a, --change-baudrate=NEW_BAUD
01160 Change baudrate from BAUD (see below) to NEW_BAUD.
01161 -c, --configure=OUTPUT
01162 Configure the device (see OUTPUT description below).
01163 -e, --echo
01164 Print MTData. It is the default if no other command is supplied.
01165 -i, --inspect
01166 Print current MT device configuration.
01167 -x, --xkf-scenario=ID
01168 Change the current XKF scenario.
01169 -l, --legacy-configure
01170 Configure the device in legacy mode (needs MODE and SETTINGS arguments
01171 below).
01172 -v, --verbose
01173 Verbose output.
01174 -y, --synchronization=settings (see below)
01175 Configure the synchronization settings of each sync line (see below)
01176 -u, --setUTCTime=time (see below)
01177 Sets the UTC time buffer of the device
01178
01179 Generic options:
01180 -d, --device=DEV
01181 Serial interface of the device (default: /dev/ttyUSB0). If 'auto', then
01182 all serial ports are tested at all baudrates and the first
01183 suitable device is used.
01184 -b, --baudrate=BAUD
01185 Baudrate of serial interface (default: 115200). If 0, then all
01186 rates are tried until a suitable one is found.
01187
01188 Configuration option:
01189 OUTPUT
01190 The format is a sequence of "<group><type><frequency>?<format>?"
01191 separated by commas.
01192 The frequency and format are optional.
01193 The groups and types can be:
01194 t temperature (max frequency: 1 Hz):
01195 tt temperature
01196 i timestamp (max frequency: 2000 Hz):
01197 iu UTC time
01198 ip packet counter
01199 ii Integer Time of the Week (ITOW)
01200 if sample time fine
01201 ic sample time coarse
01202 ir frame range
01203 o orientation data (max frequency: 400 Hz):
01204 oq quaternion
01205 om rotation matrix
01206 oe Euler angles
01207 b pressure (max frequency: 50 Hz):
01208 bp baro pressure
01209 a acceleration (max frequency: 2000 Hz (see documentation)):
01210 ad delta v
01211 aa acceleration
01212 af free acceleration
01213 ah acceleration HR (max frequency 1000 Hz)
01214 p position (max frequency: 400 Hz):
01215 pa altitude ellipsoid
01216 pp position ECEF
01217 pl latitude longitude
01218 n GNSS (max frequency: 4 Hz):
01219 np GNSS PVT data
01220 ns GNSS satellites info
01221 w angular velocity (max frequency: 2000 Hz (see documentation)):
01222 wr rate of turn
01223 wd delta q
01224 wh rate of turn HR (max frequency 1000 Hz)
01225 g GPS (max frequency: 4 Hz):
01226 gd DOP
01227 gs SOL
01228 gu time UTC
01229 gi SV info
01230 r Sensor Component Readout (max frequency: 2000 Hz):
01231 rr ACC, GYR, MAG, temperature
01232 rt Gyro temperatures
01233 m Magnetic (max frequency: 100 Hz):
01234 mf magnetic Field
01235 v Velocity (max frequency: 400 Hz):
01236 vv velocity XYZ
01237 s Status (max frequency: 2000 Hz):
01238 sb status byte
01239 sw status word
01240 Frequency is specified in decimal and is assumed to be the maximum
01241 frequency if it is omitted.
01242 Format is a combination of the precision for real valued numbers and
01243 coordinate system:
01244 precision:
01245 f single precision floating point number (32-bit) (default)
01246 d double precision floating point number (64-bit)
01247 coordinate system:
01248 e East-North-Up (default)
01249 n North-East-Down
01250 w North-West-Up
01251 Examples:
01252 The default configuration for the MTi-1/10/100 IMUs can be
01253 specified either as:
01254 "wd,ad,mf,ip,if,sw"
01255 or
01256 "wd2000fe,ad2000fe,mf100fe,ip2000,if2000,sw2000"
01257 For getting quaternion orientation in float with sample time:
01258 "oq400fw,if2000"
01259 For longitude, latitude, altitude and orientation (on MTi-G-700):
01260 "pl400fe,pa400fe,oq400fe"
01261
01262 Synchronization settings:
01263 The format follows the xsens protocol documentation. All fields are required
01264 and separated by commas.
01265 Note: The entire synchronization buffer is wiped every time a new one
01266 is set, so it is necessary to specify the settings of multiple
01267 lines at once.
01268 It also possible to clear the synchronization with the argument "clear"
01269
01270 Function (see manual for details):
01271 3 Trigger indication
01272 4 Interval Transition Measurement
01273 8 SendLatest
01274 9 ClockBiasEstimation
01275 11 StartSampling
01276 Line (manual for details):
01277 0 ClockIn
01278 1 GPSClockIn (only available for 700/710)
01279 2 Input Line (SyncIn)
01280 4 SyncOut
01281 5 ExtTimepulseIn (only available for 700/710)
01282 6 Software (only available for SendLatest with ReqData message)
01283 Polarity:
01284 1 Positive pulse/ Rising edge
01285 2 Negative pulse/ Falling edge
01286 3 Both/ Toggle
01287 Trigger Type:
01288 0 multiple times
01289 1 once
01290 Skip First (unsigned_int):
01291 Number of initial events to skip before taking actions
01292 Skip Factor (unsigned_int):
01293 Number of events to skip before taking action again
01294 Ignored with ReqData.
01295 Pulse Width (unsigned_int):
01296 Ignored for SyncIn.
01297 For SyncOut, the width of the generated pulse in 100 microseconds
01298 unit. Ignored for Toggle pulses.
01299 Delay:
01300 Delay after receiving a sync pulse to taking action,
01301 100 microseconds units, range [0...600000]
01302 Clock Period:
01303 Reference clock period in milliseconds for ClockBiasEstimation
01304 Offset:
01305 Offset from event to pulse generation.
01306 100 microseconds unit, range [-30000...+30000]
01307
01308 Examples:
01309 For changing the sync setting of the SyncIn line to trigger indication
01310 with rising edge, one time triggering and no skipping and delay. Enter
01311 the settings as:
01312 "3,2,1,1,0,0,0,0"
01313
01314 Note a number is still in the place for pulse width despite it being
01315 ignored.
01316
01317 To set multiple lines at once:
01318 ./mtdevice.py -y 3,2,1,0,0,0,0,0 -y 9,0,1,0,0,0,10,0
01319
01320 To clear the synchronization settings of MTi
01321 ./mtdevice.py -y clear
01322
01323 SetUTCTime settings:
01324 There are two ways to set the UTCtime for the MTi.
01325 Option #1: set MTi to the current UTC time based on local system time with
01326 the option 'now'
01327 Option #2: set MTi to a specified UTC time
01328 The time fields are set as follows:
01329 year: range [1999,2099]
01330 month: range [1,12]
01331 day: day of the month, range [1,31]
01332 hour: hour of the day, range [0,23]
01333 min: minute of the hour, range [0,59]
01334 sec: second of the minute, range [0,59]
01335 ns: nanosecond of the second, range [0,1000000000]
01336 flag:
01337 1: Valid Time of Week
01338 2: Valid Week Number
01339 4: valid UTC
01340 Note: the flag is ignored for setUTCTime as it is set by the module
01341 itself when connected to a GPS
01342
01343 Examples:
01344 Set UTC time for the device:
01345 ./mtdevice.py -u now
01346 ./mtdevice.py -u 1999,1,1,0,0,0,0,0
01347
01348 Legacy options:
01349 -m, --output-mode=MODE
01350 Legacy mode of the device to select the information to output.
01351 This is required for 'legacy-configure' command.
01352 MODE can be either the mode value in hexadecimal, decimal or
01353 binary form, or a string composed of the following characters
01354 (in any order):
01355 t temperature, [0x0001]
01356 c calibrated data, [0x0002]
01357 o orientation data, [0x0004]
01358 a auxiliary data, [0x0008]
01359 p position data (requires MTi-G), [0x0010]
01360 v velocity data (requires MTi-G), [0x0020]
01361 s status data, [0x0800]
01362 g raw GPS mode (requires MTi-G), [0x1000]
01363 r raw (incompatible with others except raw GPS), [0x4000]
01364 For example, use "--output-mode=so" to have status and
01365 orientation data.
01366 -s, --output-settings=SETTINGS
01367 Legacy settings of the device. This is required for 'legacy-configure'
01368 command.
01369 SETTINGS can be either the settings value in hexadecimal,
01370 decimal or binary form, or a string composed of the following
01371 characters (in any order):
01372 t sample count (excludes 'n')
01373 n no sample count (excludes 't')
01374 u UTC time
01375 q orientation in quaternion (excludes 'e' and 'm')
01376 e orientation in Euler angles (excludes 'm' and 'q')
01377 m orientation in matrix (excludes 'q' and 'e')
01378 A acceleration in calibrated data
01379 G rate of turn in calibrated data
01380 M magnetic field in calibrated data
01381 i only analog input 1 (excludes 'j')
01382 j only analog input 2 (excludes 'i')
01383 N North-East-Down instead of default: X North Z up
01384 For example, use "--output-settings=tqMAG" for all calibrated
01385 data, sample counter and orientation in quaternion.
01386 -p, --period=PERIOD
01387 Sampling period in (1/115200) seconds (default: 1152).
01388 Minimum is 225 (1.95 ms, 512 Hz), maximum is 1152
01389 (10.0 ms, 100 Hz).
01390 Note that for legacy devices it is the period at which sampling occurs,
01391 not the period at which messages are sent (see below).
01392
01393 Deprecated options:
01394 -f, --deprecated-skip-factor=SKIPFACTOR
01395 Only for mark III devices.
01396 Number of samples to skip before sending MTData message
01397 (default: 0).
01398 The frequency at which MTData message is send is:
01399 115200/(PERIOD * (SKIPFACTOR + 1))
01400 If the value is 0xffff, no data is send unless a ReqData request
01401 is made.
01402 """
01403
01404
01405
01406
01407
01408 def main():
01409
01410 shopts = 'hra:c:eild:b:y:u:m:s:p:f:x:v'
01411 lopts = ['help', 'reset', 'change-baudrate=', 'configure=', 'echo',
01412 'inspect', 'legacy-configure', 'device=', 'baudrate=',
01413 'output-mode=', 'output-settings=', 'period=',
01414 'deprecated-skip-factor=', 'xkf-scenario=', 'verbose',
01415 'synchronization=', 'setUTCtime=']
01416 try:
01417 opts, args = getopt.gnu_getopt(sys.argv[1:], shopts, lopts)
01418 except getopt.GetoptError, e:
01419 print e
01420 usage()
01421 return 1
01422
01423 device = '/dev/ttyUSB0'
01424 baudrate = 115200
01425 mode = None
01426 settings = None
01427 period = None
01428 skipfactor = None
01429 new_baudrate = None
01430 new_xkf = None
01431 actions = []
01432 verbose = False
01433 sync_settings = []
01434
01435
01436 for o, a in opts:
01437 if o in ('-h', '--help'):
01438 usage()
01439 return
01440 elif o in ('-r', '--reset'):
01441 actions.append('reset')
01442 elif o in ('-a', '--change-baudrate'):
01443 try:
01444 new_baudrate = int(a)
01445 except ValueError:
01446 print "change-baudrate argument must be integer."
01447 return 1
01448 actions.append('change-baudrate')
01449 elif o in ('-c', '--configure'):
01450 output_config = get_output_config(a)
01451 if output_config is None:
01452 return 1
01453 actions.append('configure')
01454 elif o in ('-e', '--echo'):
01455 actions.append('echo')
01456 elif o in ('-i', '--inspect'):
01457 actions.append('inspect')
01458 elif o in ('-l', '--legacy-configure'):
01459 actions.append('legacy-configure')
01460 elif o in ('-x', '--xkf-scenario'):
01461 try:
01462 new_xkf = int(a)
01463 except ValueError:
01464 print "xkf-scenario argument must be integer."
01465 return 1
01466 actions.append('xkf-scenario')
01467 elif o in ('-y', '--synchronization'):
01468 new_sync_settings = get_synchronization_settings(a)
01469 if new_sync_settings is None:
01470 return 1
01471 sync_settings.append(new_sync_settings)
01472 actions.append('synchronization')
01473 elif o in ('-u', '--setUTCtime'):
01474 UTCtime_settings = get_UTCtime(a)
01475 if UTCtime_settings is None:
01476 return 1
01477 actions.append('setUTCtime')
01478 elif o in ('-d', '--device'):
01479 device = a
01480 elif o in ('-b', '--baudrate'):
01481 try:
01482 baudrate = int(a)
01483 except ValueError:
01484 print "baudrate argument must be integer."
01485 return 1
01486 elif o in ('-m', '--output-mode'):
01487 mode = get_mode(a)
01488 if mode is None:
01489 return 1
01490 elif o in ('-s', '--output-settings'):
01491 settings = get_settings(a)
01492 if settings is None:
01493 return 1
01494 elif o in ('-p', '--period'):
01495 try:
01496 period = int(a)
01497 except ValueError:
01498 print "period argument must be integer."
01499 return 1
01500 elif o in ('-f', '--skip-factor'):
01501 try:
01502 skipfactor = int(a)
01503 except ValueError:
01504 print "skip-factor argument must be integer."
01505 return 1
01506 elif o in ('-v', '--verbose'):
01507 verbose = True
01508
01509 if len(actions) == 0:
01510 actions.append('echo')
01511 try:
01512 if device == 'auto':
01513 devs = find_devices(verbose)
01514 if devs:
01515 print "Detected devices:", "".join('\n\t%s @ %d' % (d, p)
01516 for d, p in devs)
01517 print "Using %s @ %d" % devs[0]
01518 device, baudrate = devs[0]
01519 else:
01520 print "No suitable device found."
01521 return 1
01522
01523 if not baudrate:
01524 baudrate = find_baudrate(device, verbose)
01525 if not baudrate:
01526 print "No suitable baudrate found."
01527 return 1
01528
01529 try:
01530 mt = MTDevice(device, baudrate, verbose=verbose)
01531 except serial.SerialException:
01532 raise MTException("unable to open %s" % device)
01533
01534 if 'inspect' in actions:
01535 inspect(mt, device, baudrate)
01536 if 'change-baudrate' in actions:
01537 print "Changing baudrate from %d to %d:" % (baudrate, new_baudrate),
01538 sys.stdout.flush()
01539 mt.ChangeBaudrate(new_baudrate)
01540 print " Ok"
01541 if 'reset' in actions:
01542 print "Restoring factory defaults",
01543 sys.stdout.flush()
01544 mt.RestoreFactoryDefaults()
01545 print " Ok"
01546 if 'configure' in actions:
01547 print "Changing output configuration",
01548 sys.stdout.flush()
01549 mt.SetOutputConfiguration(output_config)
01550 print " Ok"
01551 if 'synchronization' in actions:
01552 print "Changing synchronization settings",
01553 sys.stdout.flush()
01554 mt.SetSyncSettings(sync_settings)
01555 print " Ok"
01556 if 'setUTCtime' in actions:
01557 print "Setting UTC time in the device",
01558 sys.stdout.flush()
01559 mt.SetUTCTime(UTCtime_settings[6],
01560 UTCtime_settings[0],
01561 UTCtime_settings[1],
01562 UTCtime_settings[2],
01563 UTCtime_settings[3],
01564 UTCtime_settings[4],
01565 UTCtime_settings[5],
01566 UTCtime_settings[7])
01567 print " Ok"
01568 if 'legacy-configure' in actions:
01569 if mode is None:
01570 print "output-mode is require to configure the device in "\
01571 "legacy mode."
01572 return 1
01573 if settings is None:
01574 print "output-settings is required to configure the device in "\
01575 "legacy mode."
01576 return 1
01577 print "Configuring in legacy mode",
01578 sys.stdout.flush()
01579 mt.configure_legacy(mode, settings, period, skipfactor)
01580 print " Ok"
01581 if 'xkf-scenario' in actions:
01582 print "Changing XKF scenario",
01583 sys.stdout.flush()
01584 mt.SetCurrentScenario(new_xkf)
01585 print "Ok"
01586 if 'echo' in actions:
01587
01588
01589
01590 try:
01591 while True:
01592 print mt.read_measurement(mode, settings)
01593 except KeyboardInterrupt:
01594 pass
01595 except MTErrorMessage as e:
01596 print "MTErrorMessage:", e
01597 except MTException as e:
01598 print "MTException:", e
01599
01600
01601 def inspect(mt, device, baudrate):
01602 """Inspection."""
01603 def config_fmt(config):
01604 """Hexadecimal configuration."""
01605 return '[%s]' % ', '.join('(0x%04X, %d)' % (mode, freq)
01606 for (mode, freq) in config)
01607
01608 def hex_fmt(size=4):
01609 """Factory for hexadecimal representation formatter."""
01610 fmt = '0x%%0%dX' % (2*size)
01611
01612 def f(value):
01613 """Hexadecimal representation."""
01614
01615 return fmt % value
01616 return f
01617
01618 def sync_fmt(settings):
01619 """Synchronization settings: N*12 bytes"""
01620 return '[%s]' % ', '.join('(0x%02X, 0x%02X, 0x%02X, 0x%02X,'
01621 ' 0x%04X, 0x%04X, 0x%04X, 0x%04X)' % s
01622 for s in settings)
01623
01624 def try_message(m, f, formater=None, *args, **kwargs):
01625 print ' %s ' % m,
01626 try:
01627 if formater is not None:
01628 print formater(f(*args, **kwargs))
01629 else:
01630 pprint.pprint(f(*args, **kwargs), indent=4)
01631 except MTErrorMessage as e:
01632 if e.code == 0x04:
01633 print 'message unsupported by your device.'
01634 else:
01635 raise e
01636 print "Device: %s at %d Bd:" % (device, baudrate)
01637 try_message("device ID:", mt.GetDeviceID, hex_fmt(4))
01638 try_message("product code:", mt.GetProductCode)
01639 try_message("firmware revision:", mt.GetFirmwareRev)
01640 try_message("baudrate:", mt.GetBaudrate)
01641 try_message("error mode:", mt.GetErrorMode, hex_fmt(2))
01642 try_message("option flags:", mt.GetOptionFlags, hex_fmt(4))
01643 try_message("location ID:", mt.GetLocationID, hex_fmt(2))
01644 try_message("transmit delay:", mt.GetTransmitDelay)
01645 try_message("synchronization settings:", mt.GetSyncSettings, sync_fmt)
01646 try_message("general configuration:", mt.GetConfiguration)
01647 try_message("output configuration (mark IV devices):",
01648 mt.GetOutputConfiguration, config_fmt)
01649 try_message("string output type:", mt.GetStringOutputType)
01650 try_message("period:", mt.GetPeriod)
01651 try_message("alignment rotation sensor:", mt.GetAlignmentRotation,
01652 parameter=0)
01653 try_message("alignment rotation local:", mt.GetAlignmentRotation,
01654 parameter=1)
01655 try_message("output mode:", mt.GetOutputMode, hex_fmt(2))
01656 try_message("extended output mode:", mt.GetExtOutputMode, hex_fmt(2))
01657 try_message("output settings:", mt.GetOutputSettings, hex_fmt(4))
01658 try_message("GPS coordinates (lat, lon, alt):", mt.GetLatLonAlt)
01659 try_message("available scenarios:", mt.GetAvailableScenarios)
01660 try_message("current scenario ID:", mt.GetCurrentScenario)
01661 try_message("UTC time:", mt.GetUTCTime)
01662
01663
01664 def get_output_config(config_arg):
01665 """Parse the mark IV output configuration argument."""
01666
01667 code_dict = {
01668 'tt': (0x0810, 1),
01669 'iu': (0x1010, 2000),
01670 'ip': (0x1020, 2000),
01671 'ii': (0x1030, 2000),
01672 'if': (0x1060, 2000),
01673 'ic': (0x1070, 2000),
01674 'ir': (0x1080, 2000),
01675 'oq': (0x2010, 400),
01676 'om': (0x2020, 400),
01677 'oe': (0x2030, 400),
01678 'bp': (0x3010, 50),
01679 'ad': (0x4010, 2000),
01680 'aa': (0x4020, 2000),
01681 'af': (0x4030, 2000),
01682 'ah': (0x4040, 1000),
01683 'pa': (0x5020, 400),
01684 'pp': (0x5030, 400),
01685 'pl': (0x5040, 400),
01686 'np': (0x7010, 4),
01687 'ns': (0x7020, 4),
01688 'wr': (0x8020, 2000),
01689 'wd': (0x8030, 2000),
01690 'wh': (0x8040, 1000),
01691 'gd': (0x8830, 4),
01692 'gs': (0x8840, 4),
01693 'gu': (0x8880, 4),
01694 'gi': (0x88A0, 4),
01695 'rr': (0xA010, 2000),
01696 'rt': (0xA020, 2000),
01697 'mf': (0xC020, 100),
01698 'vv': (0xD010, 400),
01699 'sb': (0xE010, 2000),
01700 'sw': (0xE020, 2000)
01701 }
01702
01703 format_dict = {'f': 0x00, 'd': 0x03, 'e': 0x00, 'n': 0x04, 'w': 0x08}
01704 config_re = re.compile('([a-z]{2})(\d+)?([fdenw])?([fdnew])?')
01705 output_configuration = []
01706 try:
01707 for item in config_arg.split(','):
01708 group, frequency, fmt1, fmt2 = config_re.findall(item.lower())[0]
01709 code, max_freq = code_dict[group]
01710 if fmt1 in format_dict:
01711 code |= format_dict[fmt1]
01712 if fmt2 in format_dict:
01713 code |= format_dict[fmt2]
01714 if frequency:
01715 frequency = min(max_freq, int(frequency))
01716 else:
01717 frequency = max_freq
01718 output_configuration.append((code, frequency))
01719 return output_configuration
01720 except (IndexError, KeyError):
01721 print 'could not parse output specification "%s"' % item
01722 return
01723
01724
01725 def get_mode(arg):
01726 """Parse command line output-mode argument."""
01727 try:
01728 mode = int(arg)
01729 return mode
01730 except ValueError:
01731 pass
01732 if arg[0] == '0':
01733 try:
01734 mode = int(arg, 2)
01735 return mode
01736 except ValueError:
01737 pass
01738 try:
01739 mode = int(arg, 16)
01740 return mode
01741 except ValueError:
01742 pass
01743
01744 mode = 0
01745 for c in arg:
01746 if c == 't':
01747 mode |= OutputMode.Temp
01748 elif c == 'c':
01749 mode |= OutputMode.Calib
01750 elif c == 'o':
01751 mode |= OutputMode.Orient
01752 elif c == 'a':
01753 mode |= OutputMode.Auxiliary
01754 elif c == 'p':
01755 mode |= OutputMode.Position
01756 elif c == 'v':
01757 mode |= OutputMode.Velocity
01758 elif c == 's':
01759 mode |= OutputMode.Status
01760 elif c == 'g':
01761 mode |= OutputMode.RAWGPS
01762 elif c == 'r':
01763 mode |= OutputMode.RAW
01764 else:
01765 print "Unknown output-mode specifier: '%s'" % c
01766 return
01767 return mode
01768
01769
01770 def get_settings(arg):
01771 """Parse command line output-settings argument."""
01772 try:
01773 settings = int(arg)
01774 return settings
01775 except ValueError:
01776 pass
01777 if arg[0] == '0':
01778 try:
01779 settings = int(arg, 2)
01780 return settings
01781 except ValueError:
01782 pass
01783 try:
01784 settings = int(arg, 16)
01785 return settings
01786 except ValueError:
01787 pass
01788
01789 timestamp = 0
01790 orient_mode = 0
01791 calib_mode = OutputSettings.CalibMode_Mask
01792 NED = 0
01793 for c in arg:
01794 if c == 't':
01795 timestamp = OutputSettings.Timestamp_SampleCnt
01796 elif c == 'n':
01797 timestamp = OutputSettings.Timestamp_None
01798 elif c == 'u':
01799 timestamp |= OutputSettings.Timestamp_UTCTime
01800 elif c == 'q':
01801 orient_mode = OutputSettings.OrientMode_Quaternion
01802 elif c == 'e':
01803 orient_mode = OutputSettings.OrientMode_Euler
01804 elif c == 'm':
01805 orient_mode = OutputSettings.OrientMode_Matrix
01806 elif c == 'A':
01807 calib_mode &= OutputSettings.CalibMode_Acc
01808 elif c == 'G':
01809 calib_mode &= OutputSettings.CalibMode_Gyr
01810 elif c == 'M':
01811 calib_mode &= OutputSettings.CalibMode_Mag
01812 elif c == 'i':
01813 calib_mode &= OutputSettings.AuxiliaryMode_NoAIN2
01814 elif c == 'j':
01815 calib_mode &= OutputSettings.AuxiliaryMode_NoAIN1
01816 elif c == 'N':
01817 NED = OutputSettings.Coordinates_NED
01818 else:
01819 print "Unknown output-settings specifier: '%s'" % c
01820 return
01821 settings = timestamp | orient_mode | calib_mode | NED
01822 return settings
01823
01824 def get_synchronization_settings(arg):
01825 """Parse command line synchronization-settings argument."""
01826 if arg == "clear":
01827 sync_settings = [0,0,0,0,0,0,0,0]
01828 return sync_settings
01829 else:
01830
01831 sync_settings = arg.split(',')
01832 try:
01833
01834 sync_settings = tuple([int(i) for i in sync_settings])
01835 except ValueError:
01836 print "Synchronization sync_settings must be integers."
01837 return
01838
01839 if sync_settings[0] in (3, 4, 8, 9, 11) and \
01840 sync_settings[1] in (0, 1, 2, 4, 5, 6) and \
01841 sync_settings[2] in (1, 2, 3) and \
01842 sync_settings[3] in (0, 1):
01843 return sync_settings
01844 else:
01845 print "Invalid synchronization settings."
01846 return
01847
01848
01849 def get_UTCtime(arg):
01850
01851
01852 if arg == "now":
01853 timestamp = datetime.datetime.utcnow()
01854 time_settings = []
01855 time_settings.append(timestamp.year)
01856 time_settings.append(timestamp.month)
01857 time_settings.append(timestamp.day)
01858 time_settings.append(timestamp.hour)
01859 time_settings.append(timestamp.minute)
01860 time_settings.append(timestamp.second)
01861 time_settings.append(timestamp.microsecond*1000)
01862 time_settings.append(0)
01863 return time_settings
01864 else:
01865
01866 time_settings = arg.split(',')
01867 try:
01868 time_settings = [int(i) for i in time_settings]
01869 except ValueError:
01870 print "UTCtime settings must be integers."
01871 return
01872
01873
01874 if 1999 <= time_settings[0] <= 2099 and\
01875 1 <= time_settings[1] <= 12 and\
01876 1 <= time_settings[2] <= 31 and\
01877 0 <= time_settings[3] <= 23 and\
01878 0 <= time_settings[4] <= 59 and\
01879 0 <= time_settings[5] <= 59 and\
01880 0 <= time_settings[6] <= 1000000000:
01881 return time_settings
01882 else:
01883 print "Invalid UTCtime settings."
01884 return
01885
01886
01887 if __name__ == '__main__':
01888 main()