00001
00002 import serial
00003 import struct
00004
00005 import sys, getopt, time, glob
00006
00007 from mtdef import MID, OutputMode, OutputSettings, MTException, Baudrates, XDIGroup, getName, getMIDName
00008
00009
00010 verbose = False
00011
00012
00013
00014
00015
00016 class MTDevice(object):
00017 """XSens MT device communication object."""
00018
00019 def __init__(self, port, baudrate=115200, timeout=0.001, autoconf=True,
00020 config_mode=False):
00021 """Open device."""
00022
00023 self.device = serial.Serial(port, baudrate, timeout=timeout,
00024 writeTimeout=timeout)
00025 self.device.flushInput()
00026 self.device.flushOutput()
00027
00028 self.timeout = 100*timeout
00029 if autoconf:
00030 self.auto_config()
00031 else:
00032
00033 self.mode = None
00034
00035 self.settings = None
00036
00037 self.length = None
00038
00039 self.header = None
00040 if config_mode:
00041 self.GoToConfig()
00042
00043
00044
00045
00046
00047
00048 def write_msg(self, mid, data=[]):
00049 """Low-level message sending function."""
00050 length = len(data)
00051 if length>254:
00052 lendat = [0xFF, 0xFF&length, 0xFF&(length>>8)]
00053 else:
00054 lendat = [length]
00055 packet = [0xFA, 0xFF, mid] + lendat + list(data)
00056 packet.append(0xFF&(-(sum(packet[1:]))))
00057 msg = struct.pack('%dB'%len(packet), *packet)
00058 while self.device.read():
00059
00060 pass
00061 self.device.write(msg)
00062 if verbose:
00063 print "MT: Write message id 0x%02X (%s) with %d data bytes: [%s]"%(mid, getMIDName(mid), length,
00064 ' '.join("%02X"% v for v in data))
00065
00066
00067
00068 def read_data_msg(self, buf=bytearray()):
00069 """Low-level MTData receiving function.
00070 Take advantage of known message length."""
00071 start = time.time()
00072 if self.length>254:
00073 totlength = 7 + self.length
00074 else:
00075 totlength = 5 + self.length
00076 while (time.time()-start)<self.timeout:
00077 while len(buf)<totlength:
00078 buf.extend(self.device.read(totlength-len(buf)))
00079 preamble_ind = buf.find(self.header)
00080 if preamble_ind==-1:
00081
00082
00083 del buf[:-3]
00084 continue
00085 elif preamble_ind:
00086
00087
00088 del buf[:preamble_ind]
00089
00090 while len(buf)<totlength:
00091 buf.extend(self.device.read(totlength-len(buf)))
00092 if 0xFF&sum(buf[1:]):
00093
00094
00095 del buf[:buf.find(self.header)-2]
00096 continue
00097 data = str(buf[-self.length-1:-1])
00098 del buf[:]
00099 return data
00100 else:
00101 raise MTException("could not find MTData message.")
00102
00103
00104 def read_msg(self):
00105 """Low-level message receiving function."""
00106 start = time.time()
00107 while (time.time()-start)<self.timeout:
00108 new_start = time.time()
00109
00110
00111 def waitfor(size=1):
00112 while self.device.inWaiting() < size:
00113 if time.time()-new_start >= self.timeout:
00114 raise MTException("timeout waiting for message.")
00115
00116 c = self.device.read()
00117 while (not c) and ((time.time()-new_start)<self.timeout):
00118 c = self.device.read()
00119 if not c:
00120 raise MTException("timeout waiting for message.")
00121 if ord(c)<>0xFA:
00122 continue
00123
00124 waitfor(3)
00125 if ord(self.device.read())<>0xFF:
00126 continue
00127
00128
00129 mid, length = struct.unpack('!BB', self.device.read(2))
00130 if length==255:
00131 waitfor(2)
00132 length, = struct.unpack('!H', self.device.read(2))
00133
00134
00135 waitfor(length+1)
00136 buf = self.device.read(length+1)
00137 while (len(buf)<length+1) and ((time.time()-start)<self.timeout):
00138 buf+= self.device.read(length+1-len(buf))
00139 if (len(buf)<length+1):
00140 continue
00141 checksum = ord(buf[-1])
00142 data = struct.unpack('!%dB'%length, buf[:-1])
00143 if mid == MID.Error:
00144 sys.stderr.write("MT error 0x%02X: %s."%(data[0],
00145 MID.ErrorCodes[data[0]]))
00146 if verbose:
00147 print "MT: Got message id 0x%02X (%s) with %d data bytes: [%s]"%(mid, getMIDName(mid), length,
00148 ' '.join("%02X"% v for v in data))
00149 if 0xFF&sum(data, 0xFF+mid+length+checksum):
00150 sys.stderr.write("invalid checksum; discarding data and "\
00151 "waiting for next message.\n")
00152 continue
00153 return (mid, buf[:-1])
00154 else:
00155 raise MTException("could not find message.")
00156
00157
00158 def write_ack(self, mid, data=[]):
00159 """Send a message a read confirmation."""
00160 self.write_msg(mid, data)
00161 for tries in range(100):
00162 mid_ack, data_ack = self.read_msg()
00163 if mid_ack==(mid+1):
00164 break
00165 else:
00166 raise MTException("Ack (0x%X) expected, MID 0x%X received instead"\
00167 " (after 100 tries)."%(mid+1, mid_ack))
00168 return data_ack
00169
00170
00171
00172
00173
00174
00175
00176 def Reset(self):
00177 """Reset MT device."""
00178 self.write_ack(MID.Reset)
00179
00180
00181
00182 def GoToConfig(self):
00183 """Place MT device in configuration mode."""
00184 self.write_ack(MID.GoToConfig)
00185
00186
00187
00188 def GoToMeasurement(self):
00189 """Place MT device in measurement mode."""
00190 self.write_ack(MID.GoToMeasurement)
00191
00192
00193
00194 def RestoreFactoryDefaults(self):
00195 """Restore MT device configuration to factory defaults (soft version).
00196 """
00197 self.GoToConfig()
00198 self.write_ack(MID.RestoreFactoryDef)
00199
00200
00201
00202
00203 def GetOutputMode(self):
00204 """Get current output mode.
00205 Assume the device is in Config state."""
00206 data = self.write_ack(MID.SetOutputMode)
00207 self.mode, = struct.unpack('!H', data)
00208 return self.mode
00209
00210
00211
00212
00213 def SetOutputMode(self, mode):
00214 """Select which information to output.
00215 Assume the device is in Config state."""
00216 H, L = (mode&0xFF00)>>8, mode&0x00FF
00217 self.write_ack(MID.SetOutputMode, (H, L))
00218 self.mode = mode
00219
00220
00221
00222
00223 def GetOutputSettings(self):
00224 """Get current output mode.
00225 Assume the device is in Config state."""
00226 data = self.write_ack(MID.SetOutputSettings)
00227 self.settings, = struct.unpack('!I', data)
00228 return self.settings
00229
00230
00231
00232
00233 def SetOutputSettings(self, settings):
00234 """Select how to output the information.
00235 Assume the device is in Config state."""
00236 HH, HL = (settings&0xFF000000)>>24, (settings&0x00FF0000)>>16
00237 LH, LL = (settings&0x0000FF00)>>8, settings&0x000000FF
00238 self.write_ack(MID.SetOutputSettings, (HH, HL, LH, LL))
00239 self.settings = settings
00240
00241
00242
00243
00244 def SetPeriod(self, period):
00245 """Set the period of sampling.
00246 Assume the device is in Config state."""
00247 H, L = (period&0xFF00)>>8, period&0x00FF
00248 self.write_ack(MID.SetPeriod, (H, L))
00249
00250
00251
00252
00253 def SetOutputSkipFactor(self, skipfactor):
00254 """Set the output skip factor.
00255 Assume the device is in Config state."""
00256 H, L = (skipfactor&0xFF00)>>8, skipfactor&0x00FF
00257 self.write_ack(MID.SetOutputSkipFactor, (H, L))
00258
00259
00260
00261
00262 def ReqDataLength(self):
00263 """Get data length.
00264 Assume the device is in Config state."""
00265 data = self.write_ack(MID.ReqDataLength)
00266 self.length, = struct.unpack('!H', data)
00267 self.header = '\xFA\xFF\x32'+chr(self.length)
00268 return self.length
00269
00270
00271
00272
00273 def ReqConfiguration(self):
00274 """Ask for the current configuration of the MT device.
00275 Assume the device is in Config state."""
00276 config = self.write_ack(MID.ReqConfiguration)
00277 try:
00278 masterID, period, skipfactor, _, _, _, date, time, num, deviceID,\
00279 length, mode, settings =\
00280 struct.unpack('!IHHHHI8s8s32x32xHIHHI8x', config)
00281 except struct.error:
00282 raise MTException("could not parse configuration.")
00283 self.mode = mode
00284 self.settings = settings
00285 self.length = length
00286 self.header = '\xFA\xFF\x32'+chr(length)
00287 conf = {'output-mode': mode,
00288 'output-settings': settings,
00289 'length': length,
00290 'period': period,
00291 'skipfactor': skipfactor,
00292 'Master device ID': masterID,
00293 'date': date,
00294 'time': time,
00295 'number of devices': num,
00296 'device ID': deviceID}
00297 return conf
00298
00299
00300
00301
00302 def SetBaudrate(self, brid):
00303 """Set the baudrate of the device using the baudrate id.
00304 Assume the device is in Config state."""
00305 self.write_ack(MID.SetBaudrate, (brid,))
00306
00307
00308
00309
00310 def ReqAvailableScenarios(self):
00311 """Request the available XKF scenarios on the device.
00312 Assume the device is in Config state."""
00313 scenarios_dat = self.write_ack(MID.ReqAvailableScenarios)
00314 scenarios = []
00315 try:
00316 for i in range(len(scenarios_dat)/22):
00317 scenario_type, version, label =\
00318 struct.unpack('!BB20s', scenarios_dat[22*i:22*(i+1)])
00319 scenarios.append((scenario_type, version, label.strip()))
00320
00321 self.scenarios = scenarios
00322 except struct.error:
00323 raise MTException("could not parse the available XKF scenarios.")
00324 return scenarios
00325
00326
00327
00328
00329 def ReqCurrentScenario(self):
00330 """Request the ID of the currently used XKF scenario.
00331 Assume the device is in Config state."""
00332 data = self.write_ack(MID.SetCurrentScenario)
00333
00334 self.scenario_id, = struct.unpack('!H', data)
00335 try:
00336 scenarios = self.scenarios
00337 except AttributeError:
00338 scenarios = self.ReqAvailableScenarios()
00339 for t, _, label in scenarios:
00340 if t==self.scenario_id:
00341
00342 self.scenario_label = label
00343 break
00344 else:
00345 self.scenario_label = ""
00346 return self.scenario_id, self.scenario_label
00347
00348
00349
00350
00351 def SetCurrentScenario(self, scenario_id):
00352 """Sets the XKF scenario to use.
00353 Assume the device is in Config state."""
00354 self.write_ack(MID.SetCurrentScenario, (0x00, scenario_id&0xFF))
00355
00356
00357
00358
00359
00360
00361 def configure(self, mode, settings, period=None, skipfactor=None):
00362 """Configure the mode and settings of the MT device."""
00363 self.GoToConfig()
00364 self.SetOutputMode(mode)
00365 self.SetOutputSettings(settings)
00366 if period is not None:
00367 self.SetPeriod(period)
00368 if skipfactor is not None:
00369 self.SetOutputSkipFactor(skipfactor)
00370
00371 self.GetOutputMode()
00372 self.GetOutputSettings()
00373 self.ReqDataLength()
00374 self.GoToMeasurement()
00375
00376
00377
00378 def auto_config(self):
00379 """Read configuration from device."""
00380 self.GoToConfig()
00381 self.ReqConfiguration()
00382 self.GoToMeasurement()
00383 return self.mode, self.settings, self.length
00384
00385
00386
00387
00388
00389
00390
00391
00392 def read_measurement(self, mode=None, settings=None):
00393
00394
00395 mid, data = self.read_msg()
00396 if mid==MID.MTData:
00397 return self.parse_MTData(data, mode, settings)
00398 elif mid==MID.MTData2:
00399 return self.parse_MTData2(data)
00400 else:
00401 raise MTException("unknown data message: mid=0x%02X (%s)."% (mid, getMIDName(mid)))
00402
00403
00404 def parse_MTData2(self, data):
00405
00406 def parse_temperature(data_id, content, ffmt):
00407 o = {}
00408 if (data_id&0x00F0) == 0x10:
00409 o['Temp'], = struct.unpack('!'+ffmt, content)
00410 else:
00411 raise MTException("unknown packet: 0x%04X."%data_id)
00412 return o
00413 def parse_timestamp(data_id, content, ffmt):
00414 o = {}
00415 if (data_id&0x00F0) == 0x10:
00416 o['ns'], o['Year'], o['Month'], o['Day'], o['Hour'],\
00417 o['Minute'], o['Second'], o['Flags'] =\
00418 struct.unpack('!LHBBBBBB', content)
00419 elif (data_id&0x00F0) == 0x20:
00420 o['PacketCounter'], = struct.unpack('!H', content)
00421 elif (data_id&0x00F0) == 0x30:
00422 o['TimeOfWeek'], = struct.unpack('!L', content)
00423 elif (data_id&0x00F0) == 0x40:
00424 o['gpsAge'], = struct.unpack('!B', content)
00425 elif (data_id&0x00F0) == 0x50:
00426 o['pressureAge'], = struct.unpack('!B', content)
00427 elif (data_id&0x00F0) == 0x60:
00428 o['SampleTimeFine'], = struct.unpack('!L', content)
00429 elif (data_id&0x00F0) == 0x70:
00430 o['SampleTimeCoarse'], = struct.unpack('!L', content)
00431 elif (data_id&0x00F0) == 0x80:
00432 o['startFrame'], o['endFrame'] = struct.unpack('!HH', content)
00433 else:
00434 raise MTException("unknown packet: 0x%04X."%data_id)
00435 return o
00436 def parse_orientation_data(data_id, content, ffmt):
00437 o = {}
00438 if (data_id&0x00F0) == 0x10:
00439 o['Q0'], o['Q1'], o['Q2'], o['Q3'] = struct.unpack('!'+4*ffmt,
00440 content)
00441 elif (data_id&0x00F0) == 0x20:
00442 o['a'], o['b'], o['c'], o['d'], o['e'], o['f'], o['g'], o['h'],\
00443 o['i'] = struct.unpack('!'+9*ffmt, content)
00444 elif (data_id&0x00F0) == 0x30:
00445 o['Roll'], o['Pitch'], o['Yaw'] = struct.unpack('!'+3*ffmt,
00446 content)
00447 else:
00448 raise MTException("unknown packet: 0x%04X."%data_id)
00449 return o
00450 def parse_pressure(data_id, content, ffmt):
00451 o = {}
00452 if (data_id&0x00F0) == 0x10:
00453
00454 o['Pressure'], = struct.unpack('!L', content)
00455 else:
00456 raise MTException("unknown packet: 0x%04X."%data_id)
00457 return o
00458 def parse_acceleration(data_id, content, ffmt):
00459 o = {}
00460 if (data_id&0x00F0) == 0x10:
00461 o['Delta v.x'], o['Delta v.y'], o['Delta v.z'] = \
00462 struc.unpack('!'+3*ffmt, content)
00463 elif (data_id&0x00F0) == 0x20:
00464 o['accX'], o['accY'], o['accZ'] = \
00465 struc.unpack('!'+3*ffmt, content)
00466 elif (data_id&0x00F0) == 0x30:
00467 o['freeAccX'], o['freeAccY'], o['freeAccZ'] = \
00468 struc.unpack('!'+3*ffmt, content)
00469 else:
00470 raise MTException("unknown packet: 0x%04X."%data_id)
00471 return o
00472 def parse_position(data_id, content, ffmt):
00473 o = {}
00474 if (data_id&0x00F0) == 0x10:
00475 o['altMsl'], = struct.unpack('!'+ffmt, content)
00476 elif (data_id&0x00F0) == 0x20:
00477 o['altEllipsoid'], = struct.unpack('!'+ffmt, content)
00478 elif (data_id&0x00F0) == 0x30:
00479 o['ecefX'], o['ecefY'], o['ecefZ'] = \
00480 struct.unpack('!'+3*ffmt, content)
00481 elif (data_id&0x00F0) == 0x40:
00482 o['lat'], o['lon'] = struct.unpack('!'+2*ffmt, content)
00483 else:
00484 raise MTException("unknown packet: 0x%04X."%data_id)
00485 return o
00486 def parse_angular_velocity(data_id, content, ffmt):
00487 o = {}
00488
00489 if (data_id&0x00F0) == 0x20:
00490 o['gyrX'], o['gyrY'], o['gyrZ'] = \
00491 struct.unpack('!'+3*ffmt, content)
00492 elif (data_id&0x00F0) == 0x30:
00493 o['Delta q0'], o['Delta q1'], o['Delta q2'], o['Delta q3'] = \
00494 struct.unpack('!'+4*ffmt, content)
00495 else:
00496 raise MTException("unknown packet: 0x%04X."%data_id)
00497 return o
00498 def parse_GPS(data_id, content, ffmt):
00499 o = {}
00500 if (data_id&0x00F0) == 0x30:
00501 o['iTOW'], g, p, t, v, h, n, e = \
00502 struct.unpack('!LHHHHHHH', content)
00503 o['gDOP'], o['pDOP'], o['tDOP'], o['vDOP'], o['hDOP'], \
00504 o['nDOP'], o['eDOP'] = 0.01*g, 0.01*p, 0.01*t, \
00505 0.01*v, 0.01*h, 0.01*n, 0.01*e
00506 elif (data_id&0x00F0) == 0x40:
00507 o['iTOW'], o['fTOW'], o['Week'], o['gpsFix'], o['Flags'], \
00508 o['ecefX'], o['ecefY'], o['ecefZ'], o['pAcc'], \
00509 o['ecefVX'], o['ecefVY'], o['ecefVZ'], o['sAcc'], \
00510 o['pDOP'], o['numSV'] = \
00511 struct.unpack('!LlhBBlllLlllLHxBx', content)
00512 elif (data_id&0x00F0) == 0x80:
00513 o['iTOW'], o['tAcc'], o['nano'], o['year'], o['month'], \
00514 o['day'], o['hour'], o['min'], o['sec'], o['valid'] = \
00515 struct.unpack('!LLlHBBBBBB', content)
00516 elif (data_id&0x00F0) == 0xA0:
00517 o['iTOW'], o['numCh'] = struct.unpack('!LBxx', content[:8])
00518 channels = []
00519 for i in range(numCh):
00520 ch['chn'], ch['svid'], ch['flags'], ch['quality'], \
00521 ch['cno'], ch['elev'], ch['azim'], ch['prRes'] = \
00522 struct.unpack('!BBBBBbhl', content[8+12*i:20+12*i])
00523 channels.append(ch)
00524 o['channels'] = channels
00525 else:
00526 raise MTException("unknown packet: 0x%04X."%data_id)
00527 return o
00528 def parse_SCR(data_id, content, ffmt):
00529 o = {}
00530 if (data_id&0x00F0) == 0x10:
00531 o['accX'], o['accY'], o['accZ'], o['gyrX'], o['gyrY'], \
00532 o['gyrZ'], o['magX'], o['magY'], o['magZ'], o['Temp']=\
00533 struct.unpack("!9Hh", content)
00534 elif (data_id&0x00F0) == 0x20:
00535 o['tempGyrX'], o['tempGyrY'], o['tempGyrZ'] = \
00536 struct.unpack("!hhh", content)
00537 else:
00538 raise MTException("unknown packet: 0x%04X."%data_id)
00539 return o
00540 def parse_analog_in(data_id, content, ffmt):
00541 o = {}
00542 if (data_id&0x00F0) == 0x10:
00543 o['analogIn1'], = struct.unpack("!H", content)
00544 elif (data_id&0x00F0) == 0x20:
00545 o['analogIn2'], = struct.unpack("!H", content)
00546 else:
00547 raise MTException("unknown packet: 0x%04X."%data_id)
00548 return o
00549 def parse_magnetic(data_id, content, ffmt):
00550 o = {}
00551 if (data_id&0x00F0) == 0x20:
00552 o['magX'], o['magY'], o['magZ'] = \
00553 struct.unpack("!3"+ffmt, content)
00554 else:
00555 raise MTException("unknown packet: 0x%04X."%data_id)
00556 return o
00557 def parse_velocity(data_id, content, ffmt):
00558 o = {}
00559 if (data_id&0x00F0) == 0x10:
00560 o['velX'], o['velY'], o['velZ'] = \
00561 struct.unpack("!3"+ffmt, content)
00562 else:
00563 raise MTException("unknown packet: 0x%04X."%data_id)
00564 return o
00565 def parse_status(data_id, content, ffmt):
00566 o = {}
00567 if (data_id&0x00F0) == 0x10:
00568 o['StatusByte'], = struct.unpack("!B", content)
00569 elif (data_id&0x00F0) == 0x20:
00570 o['StatusWord'], = struct.unpack("!L", content)
00571 elif (data_id&0x00F0) == 0x40:
00572 o['RSSI'], = struct.unpack("!b", content)
00573 else:
00574 raise MTException("unknown packet: 0x%04X."%data_id)
00575 return o
00576
00577
00578 output = {}
00579 while data:
00580 try:
00581 data_id, size = struct.unpack('!HB', data[:3])
00582 if (data_id&0x0003) == 0x3:
00583 float_format = 'd'
00584 elif (data_id&0x0003) == 0x0:
00585 float_format = 'f'
00586 else:
00587 raise MTException("fixed point precision not supported.")
00588 content = data[3:3+size]
00589 data = data[3+size]
00590 group = data_id&0xFF00
00591 if group == XDIGroup.Temperature:
00592 output['Temperature'] = parse_temperature(data_id, content, ffmt)
00593 elif group == XDIGroup.Timestamp:
00594 output['Timestamp'] = parse_timestamp(data_id, content, ffmt)
00595 elif group == XDIGroup.OrientationData:
00596 output['Orientation Data'] = parse_orientation_data(data_id, content, ffmt)
00597 elif group == XDIGroup.Pressure:
00598 output['Pressure'] = parse_pressure(data_id, content, ffmt)
00599 elif group == XDIGroup.Acceleration:
00600 output['Acceleration'] = parse_acceleration(data_id, content, ffmt)
00601 elif group == XDIGroup.Position:
00602 output['Position'] = parse_position(data_id, content, ffmt)
00603 elif group == XDIGroup.AngularVelocity:
00604 output['Angular Velocity'] = parse_angular_velocity(data_id, content, ffmt)
00605 elif group == XDIGroup.GPS:
00606 output['GPS'] = parse_GPS(data_id, content, ffmt)
00607 elif group == XDIGroup.SensorComponentReadout:
00608 output['SCR'] = parse_SCR(data_id, content, ffmt)
00609 elif group == XDIGroup.AnalogIn:
00610 output['Analog In'] = parse_analog_in(data_id, content, ffmt)
00611 elif group == XDIGroup.Magnetic:
00612 output['Magnetic'] = parse_magnetic(data_id, content, ffmt)
00613 elif group == XDIGroup.Velocity:
00614 output['Velocity'] = parse_velocity(data_id, content, ffmt)
00615 elif group == XDIGroup.Status:
00616 output['Status'] = parse_status(data_id, content, ffmt)
00617 else:
00618 raise MTException("unknown XDI group: 0x%04X."%group)
00619 except struct.error, e:
00620 raise MTException("couldn't parse MTData2 message.")
00621 return output
00622
00623
00624 def parse_MTData(self, data, mode=None, settings=None):
00625 """Read and parse a measurement packet."""
00626
00627 if mode is None:
00628 mode = self.mode
00629 if settings is None:
00630 settings = self.settings
00631
00632 output = {}
00633 try:
00634
00635 if mode & OutputMode.RAW:
00636 o = {}
00637 o['accX'], o['accY'], o['accZ'], o['gyrX'], o['gyrY'], o['gyrZ'],\
00638 o['magX'], o['magY'], o['magZ'], o['temp'] =\
00639 struct.unpack('!10H', data[:20])
00640 data = data[20:]
00641 output['RAW'] = o
00642
00643 if mode & OutputMode.RAWGPS:
00644 o = {}
00645 o['Press'], o['bPrs'], o['ITOW'], o['LAT'], o['LON'], o['ALT'],\
00646 o['VEL_N'], o['VEL_E'], o['VEL_D'], o['Hacc'], o['Vacc'],\
00647 o['Sacc'], o['bGPS'] = struct.unpack('!HBI6i3IB', data[:44])
00648 data = data[44:]
00649 output['RAWGPS'] = o
00650
00651 if mode & OutputMode.Temp:
00652 temp, = struct.unpack('!f', data[:4])
00653 data = data[4:]
00654 output['Temp'] = temp
00655
00656 if mode & OutputMode.Calib:
00657 o = {}
00658 if not (settings&OutputSettings.CalibMode_GyrMag):
00659 o['accX'], o['accY'], o['accZ'] = struct.unpack('!3f',\
00660 data[:12])
00661 data = data[12:]
00662 if not (settings&OutputSettings.CalibMode_AccMag):
00663 o['gyrX'], o['gyrY'], o['gyrZ'] = struct.unpack('!3f',\
00664 data[:12])
00665 data = data[12:]
00666 if not (settings&OutputSettings.CalibMode_AccGyr):
00667 o['magX'], o['magY'], o['magZ'] = struct.unpack('!3f',\
00668 data[:12])
00669 data = data[12:]
00670 output['Calib'] = o
00671
00672 if mode & OutputMode.Orient:
00673 o = {}
00674 if settings & OutputSettings.OrientMode_Euler:
00675 o['roll'], o['pitch'], o['yaw'] = struct.unpack('!3f', data[:12])
00676 data = data[12:]
00677 elif settings & OutputSettings.OrientMode_Matrix:
00678 a, b, c, d, e, f, g, h, i = struct.unpack('!9f', data[:36])
00679 data = data[36:]
00680 o['matrix'] = ((a, b, c), (d, e, f), (g, h, i))
00681 else:
00682 q0, q1, q2, q3 = struct.unpack('!4f', data[:16])
00683 data = data[16:]
00684 o['quaternion'] = (q0, q1, q2, q3)
00685 output['Orient'] = o
00686
00687 if mode & OutputMode.Auxiliary:
00688 o = {}
00689 if not (settings&OutputSettings.AuxiliaryMode_NoAIN1):
00690 o['Ain_1'], = struct.unpack('!H', data[:2])
00691 data = data[2:]
00692 if not (settings&OutputSettings.AuxiliaryMode_NoAIN2):
00693 o['Ain_2'], = struct.unpack('!H', data[:2])
00694 data = data[2:]
00695 output['Auxiliary'] = o
00696
00697 if mode & OutputMode.Position:
00698 o = {}
00699 o['Lat'], o['Lon'], o['Alt'] = struct.unpack('!3f', data[:12])
00700 data = data[12:]
00701 output['Pos'] = o
00702
00703 if mode & OutputMode.Velocity:
00704 o = {}
00705 o['Vel_X'], o['Vel_Y'], o['Vel_Z'] = struct.unpack('!3f', data[:12])
00706 data = data[12:]
00707 output['Vel'] = o
00708
00709 if mode & OutputMode.Status:
00710 status, = struct.unpack('!B', data[:1])
00711 data = data[1:]
00712 output['Stat'] = status
00713
00714 if settings & OutputSettings.Timestamp_SampleCnt:
00715 TS, = struct.unpack('!H', data[:2])
00716 data = data[2:]
00717 output['Sample'] = TS
00718 except struct.error, e:
00719 raise MTException("could not parse MTData message.")
00720 if data <> '':
00721 raise MTException("could not parse MTData message (too long).")
00722 return output
00723
00724
00725
00726 def ChangeBaudrate(self, baudrate):
00727 """Change the baudrate, reset the device and reopen communication."""
00728 self.GoToConfig()
00729 brid = Baudrates.get_BRID(baudrate)
00730 self.SetBaudrate(brid)
00731 self.Reset()
00732
00733 self.device.baudrate=baudrate
00734
00735 time.sleep(0.01)
00736 self.read_msg()
00737 self.write_msg(0x3f)
00738
00739
00740
00741
00742
00743
00744
00745 def find_devices():
00746 mtdev_list = []
00747 for port in glob.glob("/dev/tty*S*"):
00748 try:
00749 br = find_baudrate(port)
00750 if br:
00751 mtdev_list.append((port, br))
00752 except MTException:
00753 pass
00754 return mtdev_list
00755
00756
00757
00758
00759
00760 def find_baudrate(port):
00761 baudrates = (115200, 460800, 921600, 230400, 57600, 38400, 19200, 9600)
00762 for br in baudrates:
00763 try:
00764 mt = MTDevice(port, br)
00765 except serial.SerialException:
00766 raise MTException("unable to open %s"%port)
00767 try:
00768 mt.GoToConfig()
00769 mt.GoToMeasurement()
00770 return br
00771 except MTException:
00772 pass
00773
00774
00775
00776
00777
00778
00779 def usage():
00780 print """MT device driver.
00781 Usage:
00782 ./mtdevice.py [commands] [opts]
00783
00784 Commands:
00785 -h, --help
00786 Print this help and quit.
00787 -r, --reset
00788 Reset device to factory defaults.
00789 -a, --change-baudrate=NEW_BAUD
00790 Change baudrate from BAUD (see below) to NEW_BAUD.
00791 -c, --configure
00792 Configure the device (needs MODE and SETTINGS arguments below).
00793 -e, --echo
00794 Print MTData. It is the default if no other command is supplied.
00795 -i, --inspect
00796 Print current MT device configuration.
00797 -x, --xkf-scenario=ID
00798 Change the current XKF scenario.
00799
00800
00801 Options:
00802 -d, --device=DEV
00803 Serial interface of the device (default: /dev/ttyUSB0). If 'auto', then
00804 all serial ports are tested at all baudrates and the first
00805 suitable device is used.
00806 -b, --baudrate=BAUD
00807 Baudrate of serial interface (default: 115200). If 0, then all
00808 rates are tried until a suitable one is found.
00809 -m, --output-mode=MODE
00810 Mode of the device selecting the information to output.
00811 This is required for 'configure' command. If it is not present
00812 in 'echo' command, the configuration will be read from the
00813 device.
00814 MODE can be either the mode value in hexadecimal, decimal or
00815 binary form, or a string composed of the following characters
00816 (in any order):
00817 t temperature, [0x0001]
00818 c calibrated data, [0x0002]
00819 o orientation data, [0x0004]
00820 a auxiliary data, [0x0008]
00821 p position data (requires MTi-G), [0x0010]
00822 v velocity data (requires MTi-G), [0x0020]
00823 s status data, [0x0800]
00824 g raw GPS mode (requires MTi-G), [0x1000]
00825 r raw (incompatible with others except raw GPS),
00826 [0x4000]
00827 For example, use "--output-mode=so" to have status and
00828 orientation data.
00829 -s, --output-settings=SETTINGS
00830 Settings of the device.
00831 This is required for 'configure' command. If it is not present
00832 in 'echo' command, the configuration will be read from the
00833 device.
00834 SETTINGS can be either the settings value in hexadecimal,
00835 decimal or binary form, or a string composed of the following
00836 characters (in any order):
00837 t sample count (excludes 'n')
00838 n no sample count (excludes 't')
00839 q orientation in quaternion (excludes 'e' and 'm')
00840 e orientation in Euler angles (excludes 'm' and
00841 'q')
00842 m orientation in matrix (excludes 'q' and 'e')
00843 A acceleration in calibrated data
00844 G rate of turn in calibrated data
00845 M magnetic field in calibrated data
00846 i only analog input 1 (excludes 'j')
00847 j only analog input 2 (excludes 'i')
00848 N North-East-Down instead of default: X North Z up
00849 For example, use "--output-settings=tqMAG" for all calibrated
00850 data, sample counter and orientation in quaternion.
00851 -p, --period=PERIOD
00852 Sampling period in (1/115200) seconds (default: 1152).
00853 Minimum is 225 (1.95 ms, 512 Hz), maximum is 1152
00854 (10.0 ms, 100 Hz).
00855 Note that it is the period at which sampling occurs, not the
00856 period at which messages are sent (see below).
00857 -f, --skip-factor=SKIPFACTOR
00858 Number of samples to skip before sending MTData message
00859 (default: 0).
00860 The frequency at which MTData message is send is:
00861 115200/(PERIOD * (SKIPFACTOR + 1))
00862 If the value is 0xffff, no data is send unless a ReqData request
00863 is made.
00864 """
00865
00866
00867
00868
00869
00870 def main():
00871
00872 shopts = 'hra:ceid:b:m:s:p:f:x:'
00873 lopts = ['help', 'reset', 'change-baudrate=', 'configure', 'echo',
00874 'inspect', 'device=', 'baudrate=', 'output-mode=',
00875 'output-settings=', 'period=', 'skip-factor=', 'xkf-scenario=']
00876 try:
00877 opts, args = getopt.gnu_getopt(sys.argv[1:], shopts, lopts)
00878 except getopt.GetoptError, e:
00879 print e
00880 usage()
00881 return 1
00882
00883 device = '/dev/ttyUSB0'
00884 baudrate = 115200
00885 mode = None
00886 settings = None
00887 period = None
00888 skipfactor = None
00889 new_baudrate = None
00890 new_xkf = None
00891 actions = []
00892
00893 for o, a in opts:
00894 if o in ('-h', '--help'):
00895 usage()
00896 return
00897 if o in ('-r', '--reset'):
00898 actions.append('reset')
00899 if o in ('-a', '--change-baudrate'):
00900 try:
00901 new_baudrate = int(a)
00902 except ValueError:
00903 print "change-baudrate argument must be integer."
00904 return 1
00905 actions.append('change-baudrate')
00906 if o in ('-c', '--configure'):
00907 actions.append('configure')
00908 if o in ('-e', '--echo'):
00909 actions.append('echo')
00910 if o in ('-i', '--inspect'):
00911 actions.append('inspect')
00912 if o in ('-x', '--xkf-scenario'):
00913 try:
00914 new_xkf = int(a)
00915 except ValueError:
00916 print "xkf-scenario argument must be integer."
00917 return 1
00918 actions.append('xkf-scenario')
00919 if o in ('-d', '--device'):
00920 device = a
00921 if o in ('-b', '--baudrate'):
00922 try:
00923 baudrate = int(a)
00924 except ValueError:
00925 print "baudrate argument must be integer."
00926 return 1
00927 if o in ('-m', '--output-mode'):
00928 mode = get_mode(a)
00929 if mode is None:
00930 return 1
00931 if o in ('-s', '--output-settings'):
00932 settings = get_settings(a)
00933 if settings is None:
00934 return 1
00935 if o in ('-p', '--period'):
00936 try:
00937 period = int(a)
00938 except ValueError:
00939 print "period argument must be integer."
00940 return 1
00941 if o in ('-f', '--skip-factor'):
00942 try:
00943 skipfactor = int(a)
00944 except ValueError:
00945 print "skip-factor argument must be integer."
00946 return 1
00947
00948 if len(actions) == 0:
00949 actions.append('echo')
00950 try:
00951 if device=='auto':
00952 devs = find_devices()
00953 if devs:
00954 print "Detected devices:","".join('\n\t%s @ %d'%(d,p) for d,p in
00955 devs)
00956 print "Using %s @ %d"%devs[0]
00957 device, baudrate = devs[0]
00958 else:
00959 print "No suitable device found."
00960 return 1
00961
00962 if not baudrate:
00963 baudrate = find_baudrate(device)
00964 if not baudrate:
00965 print "No suitable baudrate found."
00966 return 1
00967
00968 try:
00969 mt = MTDevice(device, baudrate)
00970 except serial.SerialException:
00971 raise MTException("unable to open %s"%device)
00972
00973 if 'inspect' in actions:
00974 mt.GoToConfig()
00975 print "Device: %s at %d Bd:"%(device, baudrate)
00976 print "General configuration:", mt.ReqConfiguration()
00977 print "Available scenarios:", mt.ReqAvailableScenarios()
00978 print "Current scenario: %s (id: %d)"%mt.ReqCurrentScenario()[::-1]
00979 mt.GoToMeasurement()
00980 if 'change-baudrate' in actions:
00981 print "Changing baudrate from %d to %d:"%(baudrate, new_baudrate),
00982 sys.stdout.flush()
00983 mt.ChangeBaudrate(new_baudrate)
00984 print " Ok"
00985 if 'reset' in actions:
00986 print "Restoring factory defaults",
00987 sys.stdout.flush()
00988 mt.RestoreFactoryDefaults()
00989 print " Ok"
00990 if 'configure' in actions:
00991 if mode is None:
00992 print "output-mode is require to configure the device."
00993 return 1
00994 if settings is None:
00995 print "output-settings is required to configure the device."
00996 return 1
00997 print "Configuring mode and settings",
00998 sys.stdout.flush()
00999 mt.configure(mode, settings, period, skipfactor)
01000 print " Ok"
01001 if 'xkf-scenario' in actions:
01002 print "Changing XKF scenario",
01003 sys.stdout.flush()
01004 mt.GoToConfig()
01005 mt.SetCurrentScenario(new_xkf)
01006 mt.GoToMeasurement()
01007 print "Ok"
01008 if 'echo' in actions:
01009
01010
01011
01012 try:
01013 while True:
01014 print mt.read_measurement(mode, settings)
01015 except KeyboardInterrupt:
01016 pass
01017 except MTException as e:
01018
01019 print e
01020
01021
01022
01023 def get_mode(arg):
01024 """Parse command line output-mode argument."""
01025 try:
01026 mode = int(arg)
01027 return mode
01028 except ValueError:
01029 pass
01030 if arg[0]=='0':
01031 try:
01032 mode = int(arg, 2)
01033 return mode
01034 except ValueError:
01035 pass
01036 try:
01037 mode = int(arg, 16)
01038 return mode
01039 except ValueError:
01040 pass
01041
01042 mode = 0
01043 for c in arg:
01044 if c=='t':
01045 mode |= OutputMode.Temp
01046 elif c=='c':
01047 mode |= OutputMode.Calib
01048 elif c=='o':
01049 mode |= OutputMode.Orient
01050 elif c=='a':
01051 mode |= OutputMode.Auxiliary
01052 elif c=='p':
01053 mode |= OutputMode.Position
01054 elif c=='v':
01055 mode |= OutputMode.Velocity
01056 elif c=='s':
01057 mode |= OutputMode.Status
01058 elif c=='g':
01059 mode |= OutputMode.RAWGPS
01060 elif c=='r':
01061 mode |= OutputMode.RAW
01062 else:
01063 print "Unknown output-mode specifier: '%s'"%c
01064 return
01065 return mode
01066
01067 def get_settings(arg):
01068 """Parse command line output-settings argument."""
01069 try:
01070 settings = int(arg)
01071 return settings
01072 except ValueError:
01073 pass
01074 if arg[0]=='0':
01075 try:
01076 settings = int(arg, 2)
01077 return settings
01078 except ValueError:
01079 pass
01080 try:
01081 settings = int(arg, 16)
01082 return settings
01083 except ValueError:
01084 pass
01085
01086 timestamp = 0
01087 orient_mode = 0
01088 calib_mode = OutputSettings.CalibMode_Mask
01089 NED = 0
01090 for c in arg:
01091 if c=='t':
01092 timestamp = OutputSettings.Timestamp_SampleCnt
01093 elif c=='n':
01094 timestamp = OutputSettings.Timestamp_None
01095 elif c=='q':
01096 orient_mode = OutputSettings.OrientMode_Quaternion
01097 elif c=='e':
01098 orient_mode = OutputSettings.OrientMode_Euler
01099 elif c=='m':
01100 orient_mode = OutputSettings.OrientMode_Matrix
01101 elif c=='A':
01102 calib_mode &= OutputSettings.CalibMode_Acc
01103 elif c=='G':
01104 calib_mode &= OutputSettings.CalibMode_Gyr
01105 elif c=='M':
01106 calib_mode &= OutputSettings.CalibMode_Mag
01107 elif c=='i':
01108 calib_mode &= OutputSettings.AuxiliaryMode_NoAIN2
01109 elif c=='j':
01110 calib_mode &= OutputSettings.AuxiliaryMode_NoAIN1
01111 elif c=='N':
01112 NED = OutputSettings.Coordinates_NED
01113 else:
01114 print "Unknown output-settings specifier: '%s'"%c
01115 return
01116 settings = timestamp|orient_mode|calib_mode|NED
01117 return settings
01118
01119
01120 if __name__=='__main__':
01121 main()
01122