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