$search
00001 #!/usr/bin/env python 00002 import serial 00003 import struct 00004 00005 import sys, getopt, time, glob#, traceback 00006 00007 from mtdef import MID, OutputMode, OutputSettings, MTException, Baudrates 00008 00009 00010 00011 00012 ################################################################ 00013 # MTDevice class 00014 ################################################################ 00015 ## XSens MT device communication object. 00016 class MTDevice(object): 00017 """XSens MT device communication object.""" 00018 00019 def __init__(self, port, baudrate=115200, timeout=0.1, autoconf=True, 00020 config_mode=False): 00021 """Open device.""" 00022 ## serial interface to the device 00023 self.device = serial.Serial(port, baudrate, timeout=timeout, 00024 writeTimeout=timeout) 00025 self.device.flushInput() # flush to make sure the port is ready TODO 00026 self.device.flushOutput() # flush to make sure the port is ready TODO 00027 ## timeout for communication 00028 self.timeout = timeout 00029 if autoconf: 00030 self.auto_config() 00031 else: 00032 ## mode parameter of the IMU 00033 self.mode = None 00034 ## settings parameter of the IMU 00035 self.settings = None 00036 ## length of the MTData message 00037 self.length = None 00038 ## header of the MTData message 00039 self.header = None 00040 if config_mode: 00041 self.GoToConfig() 00042 00043 ############################################################ 00044 # Low-level communication 00045 ############################################################ 00046 00047 ## Low-level message sending function. 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 self.device.write(msg) 00059 # print "MT: Write message id 0x%02X with %d data bytes: [%s]"%(mid,length, 00060 # ' '.join("%02X"% v for v in data)) 00061 #self.device.flush() #TODO evaluate 00062 00063 ## Low-level MTData receiving function. 00064 # Take advantage of known message length. 00065 def read_data_msg(self, buf=bytearray()): 00066 """Low-level MTData receiving function. 00067 Take advantage of known message length.""" 00068 start = time.time() 00069 if self.length>254: 00070 totlength = 7 + self.length 00071 else: 00072 totlength = 5 + self.length 00073 while (time.time()-start)<self.timeout: 00074 while len(buf)<totlength: 00075 buf.extend(self.device.read(totlength-len(buf))) 00076 preamble_ind = buf.find(self.header) 00077 if preamble_ind==-1: # not found 00078 # discard unexploitable data 00079 #sys.stderr.write("MT: discarding (no preamble).\n") 00080 del buf[:-3] 00081 continue 00082 elif preamble_ind: # found but not at start 00083 # discard leading bytes 00084 #sys.stderr.write("MT: discarding (before preamble).\n") 00085 del buf[:preamble_ind] 00086 # complete message for checksum 00087 while len(buf)<totlength: 00088 buf.extend(self.device.read(totlength-len(buf))) 00089 if 0xFF&sum(buf[1:]): 00090 #sys.stderr.write("MT: invalid checksum; discarding data and "\ 00091 # "waiting for next message.\n") 00092 del buf[:buf.find(self.header)-2] 00093 continue 00094 data = str(buf[-self.length-1:-1]) 00095 del buf[:] 00096 return data 00097 else: 00098 raise MTException("could not find MTData message.") 00099 00100 00101 00102 ## Low-level message receiving function. 00103 def read_msg(self): 00104 """Low-level message receiving function.""" 00105 start = time.time() 00106 while (time.time()-start)<self.timeout: 00107 # read first char of preamble 00108 c = self.device.read() 00109 if not c: 00110 raise MTException("timeout waiting for message.") 00111 if ord(c)<>0xFA: 00112 continue 00113 # second part of preamble 00114 if ord(self.device.read())<>0xFF: # we assume no timeout anymore 00115 continue 00116 # read message id and length of message 00117 mid, length = struct.unpack('!BB', self.device.read(2)) 00118 if length==255: # extended length 00119 length, = struct.unpack('!H', self.device.read(2)) 00120 # read contents and checksum 00121 buf = self.device.read(length+1) 00122 while (len(buf)<length+1) and ((time.time()-start)<self.timeout): 00123 buf+= self.device.read(length+1-len(buf)) 00124 if (len(buf)<length+1): 00125 continue 00126 checksum = ord(buf[-1]) 00127 data = struct.unpack('!%dB'%length, buf[:-1]) 00128 if mid == MID.Error: 00129 sys.stderr.write("MT error 0x%02X: %s."%(data[0], 00130 MID.ErrorCodes[data[0]])) 00131 # print "MT: Got message id 0x%02X with %d data bytes: [%s]"%(mid,length, 00132 # ' '.join("%02X"% v for v in data)) 00133 if 0xFF&sum(data, 0xFF+mid+length+checksum): 00134 sys.stderr.write("invalid checksum; discarding data and "\ 00135 "waiting for next message.\n") 00136 continue 00137 return (mid, buf[:-1]) 00138 else: 00139 raise MTException("could not find message.") 00140 00141 ## Send a message and read confirmation 00142 def write_ack(self, mid, data=[]): 00143 """Send a message a read confirmation.""" 00144 self.write_msg(mid, data) 00145 for tries in range(10): 00146 mid_ack, data_ack = self.read_msg() 00147 if mid_ack==(mid+1): 00148 break 00149 else: 00150 raise MTException("Ack (0x%X) expected, MID 0x%X received instead"\ 00151 " (after 10 tries)."%(mid+1, mid_ack)) 00152 return data_ack 00153 00154 00155 00156 ############################################################ 00157 # High-level functions 00158 ############################################################ 00159 ## Reset MT device. 00160 def Reset(self): 00161 """Reset MT device.""" 00162 self.write_ack(MID.Reset) 00163 00164 00165 ## Place MT device in configuration mode. 00166 def GoToConfig(self): 00167 """Place MT device in configuration mode.""" 00168 self.write_ack(MID.GoToConfig) 00169 00170 00171 ## Place MT device in measurement mode. 00172 def GoToMeasurement(self): 00173 """Place MT device in measurement mode.""" 00174 self.write_ack(MID.GoToMeasurement) 00175 00176 00177 ## Restore MT device configuration to factory defaults (soft version). 00178 def RestoreFactoryDefaults(self): 00179 """Restore MT device configuration to factory defaults (soft version). 00180 """ 00181 self.GoToConfig() 00182 self.write_ack(MID.RestoreFactoryDef) 00183 00184 00185 ## Get current output mode. 00186 # Assume the device is in Config state. 00187 def GetOutputMode(self): 00188 """Get current output mode. 00189 Assume the device is in Config state.""" 00190 data = self.write_ack(MID.SetOutputMode) 00191 self.mode, = struct.unpack('!H', data) 00192 return self.mode 00193 00194 00195 ## Select which information to output. 00196 # Assume the device is in Config state. 00197 def SetOutputMode(self, mode): 00198 """Select which information to output. 00199 Assume the device is in Config state.""" 00200 H, L = (mode&0xFF00)>>8, mode&0x00FF 00201 self.write_ack(MID.SetOutputMode, (H, L)) 00202 00203 00204 ## Get current output mode. 00205 # Assume the device is in Config state. 00206 def GetOutputSettings(self): 00207 """Get current output mode. 00208 Assume the device is in Config state.""" 00209 data = self.write_ack(MID.SetOutputSettings) 00210 self.settings, = struct.unpack('!I', data) 00211 return self.settings 00212 00213 00214 ## Select how to output the information. 00215 # Assume the device is in Config state. 00216 def SetOutputSettings(self, settings): 00217 """Select how to output the information. 00218 Assume the device is in Config state.""" 00219 HH, HL = (settings&0xFF000000)>>24, (settings&0x00FF0000)>>16 00220 LH, LL = (settings&0x0000FF00)>>8, settings&0x000000FF 00221 self.write_ack(MID.SetOutputSettings, (HH, HL, LH, LL)) 00222 00223 00224 ## Set the period of sampling. 00225 # Assume the device is in Config state. 00226 def SetPeriod(self, period): 00227 """Set the period of sampling. 00228 Assume the device is in Config state.""" 00229 H, L = (period&0xFF00)>>8, period&0x00FF 00230 self.write_ack(MID.SetPeriod, (H, L)) 00231 00232 00233 ## Set the output skip factor. 00234 # Assume the device is in Config state. 00235 def SetOutputSkipFactor(self, skipfactor): 00236 """Set the output skip factor. 00237 Assume the device is in Config state.""" 00238 H, L = (skipfactor&0xFF00)>>8, skipfactor&0x00FF 00239 self.write_ack(MID.SetOutputSkipFactor, (H, L)) 00240 00241 00242 ## Get data length. 00243 # Assume the device is in Config state. 00244 def ReqDataLength(self): 00245 """Get data length. 00246 Assume the device is in Config state.""" 00247 data = self.write_ack(MID.ReqDataLength) 00248 self.length, = struct.unpack('!H', data) 00249 self.header = '\xFA\xFF\x32'+chr(self.length) 00250 return self.length 00251 00252 00253 ## Ask for the current configuration of the MT device. 00254 # Assume the device is in Config state. 00255 def ReqConfiguration(self): 00256 """Ask for the current configuration of the MT device. 00257 Assume the device is in Config state.""" 00258 config = self.write_ack(MID.ReqConfiguration) 00259 try: 00260 masterID, period, skipfactor, _, _, _, date, time, num, deviceID,\ 00261 length, mode, settings =\ 00262 struct.unpack('!IHHHHI8s8s32x32xHIHHI8x', config) 00263 except struct.error: 00264 raise MTException("could not parse configuration.") 00265 self.mode = mode 00266 self.settings = settings 00267 self.length = length 00268 self.header = '\xFA\xFF\x32'+chr(length) 00269 conf = {'output-mode': mode, 00270 'output-settings': settings, 00271 'length': length, 00272 'period': period, 00273 'skipfactor': skipfactor, 00274 'Master device ID': masterID, 00275 'date': date, 00276 'time': time, 00277 'number of devices': num, 00278 'device ID': deviceID} 00279 return conf 00280 00281 00282 ## Set the baudrate of the device using the baudrate id. 00283 # Assume the device is in Config state. 00284 def SetBaudrate(self, brid): 00285 """Set the baudrate of the device using the baudrate id. 00286 Assume the device is in Config state.""" 00287 self.write_ack(MID.SetBaudrate, (brid,)) 00288 00289 00290 ## Request the available XKF scenarios on the device. 00291 # Assume the device is in Config state. 00292 def ReqAvailableScenarios(self): 00293 """Request the available XKF scenarios on the device. 00294 Assume the device is in Config state.""" 00295 scenarios_dat = self.write_ack(MID.ReqAvailableScenarios) 00296 scenarios = [] 00297 try: 00298 for i in range(len(scenarios_dat)/22): 00299 scenario_type, version, label =\ 00300 struct.unpack('!BB20s', scenarios_dat[22*i:22*(i+1)]) 00301 scenarios.append((scenario_type, version, label.strip())) 00302 ## available XKF scenarios 00303 self.scenarios = scenarios 00304 except struct.error: 00305 raise MTException("could not parse the available XKF scenarios.") 00306 return scenarios 00307 00308 00309 ## Request the ID of the currently used XKF scenario. 00310 # Assume the device is in Config state. 00311 def ReqCurrentScenario(self): 00312 """Request the ID of the currently used XKF scenario. 00313 Assume the device is in Config state.""" 00314 data = self.write_ack(MID.ReqCurrentScenario) 00315 ## current XKF id 00316 self.scenario_id, = struct.unpack('!H', data) 00317 try: 00318 scenarios = self.scenarios 00319 except AttributeError: 00320 scenarios = self.ReqAvailableScenarios() 00321 for t, _, label in scenarios: 00322 if t==self.scenario_id: 00323 ## current XKF label 00324 self.scenario_label = label 00325 break 00326 else: 00327 self.scenario_label = "" 00328 return self.scenario_id, self.scenario_label 00329 00330 00331 ## Sets the XKF scenario to use. 00332 # Assume the device is in Config state. 00333 def SetCurrentScenario(self, scenario_id): 00334 """Sets the XKF scenario to use. 00335 Assume the device is in Config state.""" 00336 self.write_ack(MID.SetCurrentScenario, (0x00, scenario_id&0xFF)) 00337 00338 00339 ############################################################ 00340 # High-level utility functions 00341 ############################################################ 00342 ## Configure the mode and settings of the MT device. 00343 def configure(self, mode, settings, period=None, skipfactor=None): 00344 """Configure the mode and settings of the MT device.""" 00345 self.GoToConfig() 00346 self.SetOutputMode(mode) 00347 self.SetOutputSettings(settings) 00348 if period is not None: 00349 self.SetPeriod(period) 00350 if skipfactor is not None: 00351 self.SetOutputSkipFactor(skipfactor) 00352 00353 self.GetOutputMode() 00354 self.GetOutputSettings() 00355 self.ReqDataLength() 00356 self.GoToMeasurement() 00357 00358 00359 ## Read configuration from device. 00360 def auto_config(self): 00361 """Read configuration from device.""" 00362 self.GoToConfig() 00363 mode = self.GetOutputMode() 00364 settings = self.GetOutputSettings() 00365 length = self.ReqDataLength() 00366 self.GoToMeasurement() 00367 return mode, settings, length 00368 00369 ## Read and parse a measurement packet 00370 def read_measurement(self, mode=None, settings=None): 00371 """Read and parse a measurement packet.""" 00372 # getting mode 00373 if mode is None: 00374 mode = self.mode 00375 if settings is None: 00376 settings = self.settings 00377 # getting data 00378 data = self.read_data_msg() 00379 #_, data = self.read_msg() 00380 # data object 00381 output = {} 00382 try: 00383 # raw IMU first 00384 if mode & OutputMode.RAW: 00385 o = {} 00386 o['accX'], o['accY'], o['accZ'], o['gyrX'], o['gyrY'], o['gyrZ'],\ 00387 o['magX'], o['magY'], o['magZ'], o['temp'] =\ 00388 struct.unpack('!10H', data[:20]) 00389 data = data[20:] 00390 output['RAW'] = o 00391 # raw GPS second 00392 if mode & OutputMode.RAWGPS: 00393 o = {} 00394 o['Press'], o['bPrs'], o['ITOW'], o['LAT'], o['LON'], o['ALT'],\ 00395 o['VEL_N'], o['VEL_E'], o['VEL_D'], o['Hacc'], o['Vacc'],\ 00396 o['Sacc'], o['bGPS'] = struct.unpack('!HBI6i3IB', data[:44]) 00397 data = data[44:] 00398 output['RAWGPS'] = o 00399 # temperature 00400 if mode & OutputMode.Temp: 00401 temp, = struct.unpack('!f', data[:4]) 00402 data = data[4:] 00403 output['Temp'] = temp 00404 # calibrated data 00405 if mode & OutputMode.Calib: 00406 o = {} 00407 if not (settings&OutputSettings.CalibMode_GyrMag): 00408 o['accX'], o['accY'], o['accZ'] = struct.unpack('!3f',\ 00409 data[:12]) 00410 data = data[12:] 00411 if not (settings&OutputSettings.CalibMode_AccMag): 00412 o['gyrX'], o['gyrY'], o['gyrZ'] = struct.unpack('!3f',\ 00413 data[:12]) 00414 data = data[12:] 00415 if not (settings&OutputSettings.CalibMode_AccGyr): 00416 o['magX'], o['magY'], o['magZ'] = struct.unpack('!3f',\ 00417 data[:12]) 00418 data = data[12:] 00419 output['Calib'] = o 00420 # orientation 00421 if mode & OutputMode.Orient: 00422 o = {} 00423 if settings & OutputSettings.OrientMode_Euler: 00424 o['roll'], o['pitch'], o['yaw'] = struct.unpack('!3f', data[:12]) 00425 data = data[12:] 00426 elif settings & OutputSettings.OrientMode_Matrix: 00427 a, b, c, d, e, f, g, h, i = struct.unpack('!9f', data[:36]) 00428 data = data[36:] 00429 o['matrix'] = ((a, b, c), (d, e, f), (g, h, i)) 00430 else: # OutputSettings.OrientMode_Quaternion: 00431 q0, q1, q2, q3 = struct.unpack('!4f', data[:16]) 00432 data = data[16:] 00433 o['quaternion'] = (q0, q1, q2, q3) 00434 output['Orient'] = o 00435 # auxiliary 00436 if mode & OutputMode.Auxiliary: 00437 o = {} 00438 if not (settings&OutputSettings.AuxiliaryMode_NoAIN1): 00439 o['Ain_1'], = struct.unpack('!H', data[:2]) 00440 data = data[2:] 00441 if not (settings&OutputSettings.AuxiliaryMode_NoAIN2): 00442 o['Ain_2'], = struct.unpack('!H', data[:2]) 00443 data = data[2:] 00444 output['Auxiliary'] = o 00445 # position 00446 if mode & OutputMode.Position: 00447 o = {} 00448 o['Lat'], o['Lon'], o['Alt'] = struct.unpack('!3f', data[:12]) 00449 data = data[12:] 00450 output['Position'] = o 00451 # velocity 00452 if mode & OutputMode.Velocity: 00453 o = {} 00454 o['Vel_X'], o['Vel_Y'], o['Vel_Z'] = struct.unpack('!3f', data[:12]) 00455 data = data[12:] 00456 output['Velocity'] = o 00457 # status 00458 if mode & OutputMode.Status: 00459 status, = struct.unpack('!B', data[:1]) 00460 data = data[1:] 00461 output['Status'] = status 00462 # sample counter 00463 if settings & OutputSettings.Timestamp_SampleCnt: 00464 TS, = struct.unpack('!H', data[:2]) 00465 data = data[2:] 00466 output['Sample'] = TS 00467 except struct.error, e: 00468 raise MTException("could not parse MTData message.") 00469 if data <> '': 00470 raise MTException("could not parse MTData message (too long).") 00471 return output 00472 00473 00474 ## Change the baudrate, reset the device and reopen communication. 00475 def ChangeBaudrate(self, baudrate): 00476 """Change the baudrate, reset the device and reopen communication.""" 00477 self.GoToConfig() 00478 brid = Baudrates.get_BRID(baudrate) 00479 self.SetBaudrate(brid) 00480 self.Reset() 00481 #self.device.flush() 00482 self.device.baudrate=baudrate 00483 #self.device.flush() 00484 time.sleep(0.01) 00485 self.read_msg() 00486 self.write_msg(0x3f) 00487 00488 00489 00490 00491 ################################################################ 00492 # Auto detect port 00493 ################################################################ 00494 def find_devices(): 00495 mtdev_list = [] 00496 for port in glob.glob("/dev/tty*S*"): 00497 try: 00498 br = find_baudrate(port) 00499 if br: 00500 mtdev_list.append((port, br)) 00501 except MTException: 00502 pass 00503 return mtdev_list 00504 00505 00506 ################################################################ 00507 # Auto detect baudrate 00508 ################################################################ 00509 def find_baudrate(port): 00510 baudrates = (115200, 460800, 921600, 230400, 57600, 38400, 19200, 9600) 00511 for br in baudrates: 00512 try: 00513 mt = MTDevice(port, br) 00514 except serial.SerialException: 00515 raise MTException("unable to open %s"%port) 00516 try: 00517 mt.GoToConfig() 00518 mt.GoToMeasurement() 00519 return br 00520 except MTException: 00521 pass 00522 00523 00524 00525 ################################################################ 00526 # Documentation for stand alone usage 00527 ################################################################ 00528 def usage(): 00529 print """MT device driver. 00530 Usage: 00531 ./mtdevice.py [commands] [opts] 00532 00533 Commands: 00534 -h, --help 00535 Print this help and quit. 00536 -r, --reset 00537 Reset device to factory defaults. 00538 -a, --change-baudrate=NEW_BAUD 00539 Change baudrate from BAUD (see below) to NEW_BAUD. 00540 -c, --configure 00541 Configure the device (needs MODE and SETTINGS arguments below). 00542 -e, --echo 00543 Print MTData. It is the default if no other command is supplied. 00544 -i, --inspect 00545 Print current MT device configuration. 00546 -x, --xkf-scenario=ID 00547 Change the current XKF scenario. 00548 00549 00550 Options: 00551 -d, --device=DEV 00552 Serial interface of the device (default: /dev/ttyUSB0). If 'auto', then 00553 all serial ports are tested at all baudrates and the first 00554 suitable device is used. 00555 -b, --baudrate=BAUD 00556 Baudrate of serial interface (default: 115200). If 0, then all 00557 rates are tried until a suitable one is found. 00558 -m, --output-mode=MODE 00559 Mode of the device selecting the information to output. 00560 This is required for 'configure' command. If it is not present 00561 in 'echo' command, the configuration will be read from the 00562 device. 00563 MODE can be either the mode value in hexadecimal, decimal or 00564 binary form, or a string composed of the following characters 00565 (in any order): 00566 t temperature, [0x0001] 00567 c calibrated data, [0x0002] 00568 o orientation data, [0x0004] 00569 a auxiliary data, [0x0008] 00570 p position data (requires MTi-G), [0x0010] 00571 v velocity data (requires MTi-G), [0x0020] 00572 s status data, [0x0800] 00573 g raw GPS mode (requires MTi-G), [0x1000] 00574 r raw (incompatible with others except raw GPS), 00575 [0x4000] 00576 For example, use "--output-mode=so" to have status and 00577 orientation data. 00578 -s, --output-settings=SETTINGS 00579 Settings of the device. 00580 This is required for 'configure' command. If it is not present 00581 in 'echo' command, the configuration will be read from the 00582 device. 00583 SETTINGS can be either the settings value in hexadecimal, 00584 decimal or binary form, or a string composed of the following 00585 characters (in any order): 00586 t sample count (excludes 'n') 00587 n no sample count (excludes 't') 00588 q orientation in quaternion (excludes 'e' and 'm') 00589 e orientation in Euler angles (excludes 'm' and 00590 'q') 00591 m orientation in matrix (excludes 'q' and 'e') 00592 A acceleration in calibrated data 00593 G rate of turn in calibrated data 00594 M magnetic field in calibrated data 00595 i only analog input 1 (excludes 'j') 00596 j only analog input 2 (excludes 'i') 00597 N North-East-Down instead of default: X North Z up 00598 For example, use "--output-settings=tqMAG" for all calibrated 00599 data, sample counter and orientation in quaternion. 00600 -p, --period=PERIOD 00601 Sampling period in (1/115200) seconds (default: 1152). 00602 Minimum is 225 (1.95 ms, 512 Hz), maximum is 1152 00603 (10.0 ms, 100 Hz). 00604 Note that it is the period at which sampling occurs, not the 00605 period at which messages are sent (see below). 00606 -f, --skip-factor=SKIPFACTOR 00607 Number of samples to skip before sending MTData message 00608 (default: 0). 00609 The frequency at which MTData message is send is: 00610 115200/(PERIOD * (SKIPFACTOR + 1)) 00611 If the value is 0xffff, no data is send unless a ReqData request 00612 is made. 00613 """ 00614 00615 00616 ################################################################ 00617 # Main function 00618 ################################################################ 00619 def main(): 00620 # parse command line 00621 shopts = 'hra:ceid:b:m:s:p:f:x:' 00622 lopts = ['help', 'reset', 'change-baudrate=', 'configure', 'echo', 00623 'inspect', 'device=', 'baudrate=', 'output-mode=', 00624 'output-settings=', 'period=', 'skip-factor=', 'xkf-scenario='] 00625 try: 00626 opts, args = getopt.gnu_getopt(sys.argv[1:], shopts, lopts) 00627 except getopt.GetoptError, e: 00628 print e 00629 usage() 00630 return 1 00631 # default values 00632 device = '/dev/ttyUSB0' 00633 baudrate = 115200 00634 mode = None 00635 settings = None 00636 period = None 00637 skipfactor = None 00638 new_baudrate = None 00639 new_xkf = None 00640 actions = [] 00641 # filling in arguments 00642 for o, a in opts: 00643 if o in ('-h', '--help'): 00644 usage() 00645 return 00646 if o in ('-r', '--reset'): 00647 actions.append('reset') 00648 if o in ('-a', '--change-baudrate'): 00649 try: 00650 new_baudrate = int(a) 00651 except ValueError: 00652 print "change-baudrate argument must be integer." 00653 return 1 00654 actions.append('change-baudrate') 00655 if o in ('-c', '--configure'): 00656 actions.append('configure') 00657 if o in ('-e', '--echo'): 00658 actions.append('echo') 00659 if o in ('-i', '--inspect'): 00660 actions.append('inspect') 00661 if o in ('-x', '--xkf-scenario'): 00662 try: 00663 new_xkf = int(a) 00664 except ValueError: 00665 print "xkf-scenario argument must be integer." 00666 return 1 00667 actions.append('xkf-scenario') 00668 if o in ('-d', '--device'): 00669 device = a 00670 if o in ('-b', '--baudrate'): 00671 try: 00672 baudrate = int(a) 00673 except ValueError: 00674 print "baudrate argument must be integer." 00675 return 1 00676 if o in ('-m', '--output-mode'): 00677 mode = get_mode(a) 00678 if mode is None: 00679 return 1 00680 if o in ('-s', '--output-settings'): 00681 settings = get_settings(a) 00682 if settings is None: 00683 return 1 00684 if o in ('-p', '--period'): 00685 try: 00686 period = int(a) 00687 except ValueError: 00688 print "period argument must be integer." 00689 return 1 00690 if o in ('-f', '--skip-factor'): 00691 try: 00692 skipfactor = int(a) 00693 except ValueError: 00694 print "skip-factor argument must be integer." 00695 return 1 00696 # if nothing else: echo 00697 if len(actions) == 0: 00698 actions.append('echo') 00699 try: 00700 if device=='auto': 00701 devs = find_devices() 00702 if devs: 00703 print "Detected devices:","".join('\n\t%s @ %d'%(d,p) for d,p in 00704 devs) 00705 print "Using %s @ %d"%devs[0] 00706 device, baudrate = devs[0] 00707 else: 00708 print "No suitable device found." 00709 return 1 00710 # find baudrate 00711 if not baudrate: 00712 baudrate = find_baudrate(device) 00713 if not baudrate: 00714 print "No suitable baudrate found." 00715 return 1 00716 # open device 00717 try: 00718 mt = MTDevice(device, baudrate) 00719 except serial.SerialException: 00720 raise MTException("unable to open %s"%device) 00721 # execute actions 00722 if 'inspect' in actions: 00723 mt.GoToConfig() 00724 print "Device: %s at %d Bd:"%(device, baudrate) 00725 print "General configuration:", mt.ReqConfiguration() 00726 print "Available scenarios:", mt.ReqAvailableScenarios() 00727 print "Current scenario: %s (id: %d)"%mt.ReqCurrentScenario()[::-1] 00728 mt.GoToMeasurement() 00729 if 'change-baudrate' in actions: 00730 print "Changing baudrate from %d to %d:"%(baudrate, new_baudrate), 00731 sys.stdout.flush() 00732 mt.ChangeBaudrate(new_baudrate) 00733 print " Ok" # should we test it was actually ok? 00734 if 'reset' in actions: 00735 print "Restoring factory defaults", 00736 sys.stdout.flush() 00737 mt.RestoreFactoryDefaults() 00738 print " Ok" # should we test it was actually ok? 00739 if 'configure' in actions: 00740 if mode is None: 00741 print "output-mode is require to configure the device." 00742 return 1 00743 if settings is None: 00744 print "output-settings is required to configure the device." 00745 return 1 00746 print "Configuring mode and settings", 00747 sys.stdout.flush() 00748 mt.configure(mode, settings, period, skipfactor) 00749 print " Ok" # should we test it was actually ok? 00750 if 'xkf-scenario' in actions: 00751 print "Changing XKF scenario", 00752 sys.stdout.flush() 00753 mt.GoToConfig() 00754 mt.SetCurrentScenario(new_xkf) 00755 mt.GoToMeasurement() 00756 print "Ok" 00757 if 'echo' in actions: 00758 # if (mode is None) or (settings is None): 00759 # mode, settings, length = mt.auto_config() 00760 # print mode, settings, length 00761 try: 00762 while True: 00763 print mt.read_measurement(mode, settings) 00764 except KeyboardInterrupt: 00765 pass 00766 except MTException as e: 00767 #traceback.print_tb(sys.exc_info()[2]) 00768 print e 00769 00770 00771 00772 def get_mode(arg): 00773 """Parse command line output-mode argument.""" 00774 try: # decimal 00775 mode = int(arg) 00776 return mode 00777 except ValueError: 00778 pass 00779 if arg[0]=='0': 00780 try: # binary 00781 mode = int(arg, 2) 00782 return mode 00783 except ValueError: 00784 pass 00785 try: # hexadecimal 00786 mode = int(arg, 16) 00787 return mode 00788 except ValueError: 00789 pass 00790 # string mode specification 00791 mode = 0 00792 for c in arg: 00793 if c=='t': 00794 mode |= OutputMode.Temp 00795 elif c=='c': 00796 mode |= OutputMode.Calib 00797 elif c=='o': 00798 mode |= OutputMode.Orient 00799 elif c=='a': 00800 mode |= OutputMode.Auxiliary 00801 elif c=='p': 00802 mode |= OutputMode.Position 00803 elif c=='v': 00804 mode |= OutputMode.Velocity 00805 elif c=='s': 00806 mode |= OutputMode.Status 00807 elif c=='g': 00808 mode |= OutputMode.RAWGPS 00809 elif c=='r': 00810 mode |= OutputMode.RAW 00811 else: 00812 print "Unknown output-mode specifier: '%s'"%c 00813 return 00814 return mode 00815 00816 def get_settings(arg): 00817 """Parse command line output-settings argument.""" 00818 try: # decimal 00819 settings = int(arg) 00820 return settings 00821 except ValueError: 00822 pass 00823 if arg[0]=='0': 00824 try: # binary 00825 settings = int(arg, 2) 00826 return settings 00827 except ValueError: 00828 pass 00829 try: # hexadecimal 00830 settings = int(arg, 16) 00831 return settings 00832 except ValueError: 00833 pass 00834 # strings settings specification 00835 timestamp = 0 00836 orient_mode = 0 00837 calib_mode = OutputSettings.CalibMode_Mask 00838 NED = 0 00839 for c in arg: 00840 if c=='t': 00841 timestamp = OutputSettings.Timestamp_SampleCnt 00842 elif c=='n': 00843 timestamp = OutputSettings.Timestamp_None 00844 elif c=='q': 00845 orient_mode = OutputSettings.OrientMode_Quaternion 00846 elif c=='e': 00847 orient_mode = OutputSettings.OrientMode_Euler 00848 elif c=='m': 00849 orient_mode = OutputSettings.OrientMode_Matrix 00850 elif c=='A': 00851 calib_mode &= OutputSettings.CalibMode_Acc 00852 elif c=='G': 00853 calib_mode &= OutputSettings.CalibMode_Gyr 00854 elif c=='M': 00855 calib_mode &= OutputSettings.CalibMode_Mag 00856 elif c=='i': 00857 calib_mode &= OutputSettings.AuxiliaryMode_NoAIN2 00858 elif c=='j': 00859 calib_mode &= OutputSettings.AuxiliaryMode_NoAIN1 00860 elif c=='N': 00861 NED = OutputSettings.Coordinates_NED 00862 else: 00863 print "Unknown output-settings specifier: '%s'"%c 00864 return 00865 settings = timestamp|orient_mode|calib_mode|NED 00866 return settings 00867 00868 00869 if __name__=='__main__': 00870 main() 00871