12 from mtdef
import MID, OutputMode, OutputSettings, MTException, Baudrates, \
13 XDIGroup, getMIDName, DeviceState, DeprecatedMID, MTErrorMessage, \
21 """XSens MT device communication object.""" 23 def __init__(self, port, baudrate=115200, timeout=0.002, autoconf=True,
24 config_mode=
False, verbose=
False, initial_wait=0.1):
29 self.
device = serial.Serial(port, baudrate, timeout=timeout,
33 self.
device = serial.Serial(port, baudrate, timeout=timeout,
34 writeTimeout=timeout, rtscts=
True,
36 time.sleep(initial_wait)
37 self.device.flushInput()
38 self.device.flushOutput()
61 """Low-level message sending function.""" 64 lendat = b
'\xFF' + struct.pack(
'!H', length)
66 lendat = struct.pack(
'!B', length)
67 packet = b
'\xFA\xFF' + struct.pack(
'!B', mid) + lendat + data
68 packet += struct.pack(
'!B', 0xFF & (-(sum(map(ord, packet[1:])))))
71 while ((time.time()-start) < self.
timeout)
and self.device.read():
74 self.device.write(msg)
75 except serial.serialutil.SerialTimeoutException:
76 raise MTTimeoutException(
"writing message")
78 print "MT: Write message id 0x%02X (%s) with %d data bytes: [%s]" %\
80 ' '.join(
"%02X" % ord(v)
for v
in data))
83 """Get a given amount of data.""" 86 buf.extend(self.device.read(size-len(buf)))
90 print "waiting for %d bytes, got %d so far: [%s]" % \
91 (size, len(buf),
' '.join(
'%02X' % v
for v
in buf))
92 raise MTTimeoutException(
"waiting for message")
95 """Low-level MTData receiving function. 96 Take advantage of known message length. 100 totlength = 5 + self.
length 102 totlength = 7 + self.
length 103 while (time.time()-start) < self.
timeout:
104 buf.extend(self.
waitfor(totlength - len(buf)))
105 preamble_ind = buf.find(self.
header)
106 if preamble_ind == -1:
109 sys.stderr.write(
"MT: discarding (no preamble).\n")
115 sys.stderr.write(
"MT: discarding (before preamble).\n")
116 del buf[:preamble_ind]
118 buf.extend(self.
waitfor(totlength-len(buf)))
119 if 0xFF & sum(buf[1:]):
121 sys.stderr.write(
"MT: invalid checksum; discarding data and" 122 " waiting for next message.\n")
123 del buf[:buf.find(self.
header)-2]
125 data = str(buf[-self.
length-1:-1])
129 raise MTException(
"could not find MTData message.")
132 """Low-level message receiving function.""" 134 while (time.time()-start) < self.
timeout:
136 if ord(self.
waitfor()) != 0xFA:
139 if ord(self.
waitfor()) != 0xFF:
142 mid, length = struct.unpack(
'!BB', self.
waitfor(2))
144 length, = struct.unpack(
'!H', self.
waitfor(2))
148 data = struct.unpack(
'!%dB' % length, buf[:-1])
150 if 0xFF & sum(data, 0xFF+mid+length+checksum):
152 sys.stderr.write(
"invalid checksum; discarding data and " 153 "waiting for next message.\n")
156 print "MT: Got message id 0x%02X (%s) with %d data bytes: [%s]"\
158 ' '.join(
"%02X" % v
for v
in data))
160 raise MTErrorMessage(data[0])
161 return (mid, buf[:-1])
166 """Send a message and read confirmation.""" 168 for _
in range(n_retries):
170 if mid_ack == (mid+1):
173 print "ack (0x%02X) expected, got 0x%02X instead" % \
176 raise MTException(
"Ack (0x%02X) expected, MID 0x%02X received " 177 "instead (after %d retries)." % (mid+1, mid_ack,
182 """Switch device to config state if necessary.""" 183 if self.
state != DeviceState.Config:
187 """Switch device to measurement state if necessary.""" 188 if self.
state != DeviceState.Measurement:
194 def Reset(self, go_to_config=False):
197 If go_to_config then send WakeUpAck in order to leave the device in 204 if mid == MID.WakeUp:
206 self.
state = DeviceState.Config
208 self.
state = DeviceState.Measurement
211 """Place MT device in configuration mode.""" 213 self.
state = DeviceState.Config
216 """Place MT device in measurement mode.""" 219 self.
state = DeviceState.Measurement
222 """Get the device identifier.""" 225 deviceID, = struct.unpack(
'!I', data)
229 """Get the product code.""" 231 data = self.
write_ack(MID.ReqProductCode)
232 return str(data).strip()
235 """Get the firmware version.""" 240 major, minor, revision = struct.unpack(
'!BBB', data[:3])
241 return (major, minor, revision)
244 """Run the built-in self test.""" 247 bit_names = [
'accX',
'accY',
'accZ',
'gyrX',
'gyrY',
'gyrZ',
248 'magX',
'magY',
'magZ']
249 self_test_results = []
250 for i, name
in enumerate(bit_names):
251 self_test_results.append((name, (data >> i) & 1))
252 return self_test_results
255 """Get the current baudrate id of the device.""" 261 """Set the baudrate of the device using the baudrate id.""" 266 """Get the current error mode of the device.""" 269 error_mode, = struct.unpack(
'!H', data)
273 """Set the error mode of the device. 275 The error mode defines the way the device deals with errors (expect 277 0x0000: ignore any errors except message handling errors, 278 0x0001: in case of missing sampling instance: increase sample 279 counter and do not send error message, 280 0x0002: in case of missing sampling instance: increase sample 281 counter and send error message, 282 0x0003: in case of non-message handling error, an error message is 283 sent and the device will go into Config State. 286 data = struct.pack(
'!H', error_mode)
290 """Get the option flags (MTi-1 series).""" 292 data = self.
write_ack(MID.SetOptionFlags)
293 flags, = struct.unpack(
'!I', data)
297 """Set the option flags (MTi-1 series).""" 299 data = struct.pack(
'!II', set_flags, clear_flags)
303 """Get the location ID of the device.""" 306 location_id, = struct.unpack(
'!H', data)
310 """Set the location ID of the device (arbitrary).""" 312 data = struct.pack(
'!H', location_id)
316 """Restore MT device configuration to factory defaults (soft version). 322 """Get the transmission delay (only RS485).""" 324 data = self.
write_ack(MID.SetTransmitDelay)
325 transmit_delay, = struct.unpack(
'!H', data)
326 return transmit_delay
329 """Set the transmission delay (only RS485).""" 331 data = struct.pack(
'!H', transmit_delay)
332 self.
write_ack(MID.SetTransmitDelay, data)
335 """Get the synchronisation settings.""" 337 data = self.
write_ack(MID.SetSyncSettings)
338 sync_settings = [struct.unpack(
'!BBBBHHHH', data[o:o+12])
339 for o
in range(0, len(data), 12)]
343 """Set the synchronisation settings (mark IV)""" 345 data = b
''.join(struct.pack(
'!BBBBHHHH', *sync_setting)
346 for sync_setting
in sync_settings)
347 self.
write_ack(MID.SetSyncSettings, data)
350 """Ask for the current configuration of the MT device.""" 352 config = self.
write_ack(MID.ReqConfiguration)
354 masterID, period, skipfactor, _, _, _, date, time, num, deviceID,\
355 length, mode, settings =\
356 struct.unpack(
'!IHHHHI8s8s32x32xHIHHI8x', config)
358 raise MTException(
"could not parse configuration.")
363 self.
header = b
'\xFA\xFF\x32' + struct.pack(
'!B', self.
length)
365 self.
header = b
'\xFA\xFF\x32\xFF' + struct.pack(
'!H', self.
length)
366 conf = {
'output-mode': mode,
367 'output-settings': settings,
370 'skipfactor': skipfactor,
371 'Master device ID': masterID,
374 'number of devices': num,
375 'device ID': deviceID}
379 """Get the output configuration of the device (mark IV).""" 381 data = self.
write_ack(MID.SetOutputConfiguration)
382 output_configuration = [struct.unpack(
'!HH', data[o:o+4])
383 for o
in range(0, len(data), 4)]
384 return output_configuration
387 """Set the output configuration of the device (mark IV).""" 389 data = b
''.join(struct.pack(
'!HH', *output)
390 for output
in output_configuration)
391 self.
write_ack(MID.SetOutputConfiguration, data)
394 """Get the NMEA data output configuration.""" 396 data = self.
write_ack(MID.SetStringOutputType)
397 string_output_type, = struct.unpack(
'!H', data)
398 return string_output_type
401 """Set the configuration of the NMEA data output.""" 403 data = struct.pack(
'!H', string_output_type)
404 self.
write_ack(MID.SetStringOutputType, data)
407 """Get the sampling period.""" 410 period, = struct.unpack(
'!H', data)
414 """Set the sampling period.""" 416 data = struct.pack(
'!H', period)
420 """Get the object alignment. 422 parameter indicates the desired alignment quaternion: 423 0 for sensor alignment (RotSensor), 424 1 for local alignment (RotLocal). 427 data = struct.pack(
'!B', parameter)
428 data = self.
write_ack(MID.SetAlignmentRotation, data)
430 q0, q1, q2, q3 = struct.unpack(
'!ffff', data)
431 return parameter, (q0, q1, q2, q3)
432 elif len(data) == 17:
433 param, q0, q1, q2, q3 = struct.unpack(
'!Bffff', data)
434 return param, (q0, q1, q2, q3)
436 raise MTException(
'Could not parse ReqAlignmentRotationAck message:' 437 ' wrong size of message (%d instead of either 16 ' 438 'or 17).' % len(data))
441 """Set the object alignment. 443 parameter indicates the desired alignment quaternion: 444 0 for sensor alignment (RotSensor), 445 1 for local alignment (RotLocal). 448 data = struct.pack(
'!Bffff', parameter, *quaternion)
449 self.
write_ack(MID.SetAlignmentRotation, data)
452 """Get current output mode.""" 455 self.
mode, = struct.unpack(
'!H', data)
459 """Select which information to output.""" 461 data = struct.pack(
'!H', mode)
466 """Get current extended output mode (for alternative UART).""" 468 data = self.
write_ack(MID.SetExtOutputMode)
469 ext_mode, = struct.unpack(
'!H', data)
473 """Set extended output mode (for alternative UART).""" 475 data = struct.pack(
'!H', ext_mode)
476 self.
write_ack(MID.SetExtOutputMode, data)
479 """Get current output mode.""" 481 data = self.
write_ack(MID.SetOutputSettings)
482 self.
settings, = struct.unpack(
'!I', data)
486 """Select how to output the information.""" 488 data = struct.pack(
'!I', settings)
489 self.
write_ack(MID.SetOutputSettings, data)
493 """Set the output skip factor.""" 495 data = struct.pack(
'!H', skipfactor)
496 self.
write_ack(DeprecatedMID.SetOutputSkipFactor, data)
499 """Get data length for mark III devices.""" 502 data = self.
write_ack(DeprecatedMID.ReqDataLength)
503 except MTErrorMessage
as e:
505 sys.stderr.write(
"ReqDataLength message is deprecated and not " 506 "recognised by your device.")
509 self.
length, = struct.unpack(
'!H', data)
511 self.
header = b
'\xFA\xFF\x32' + struct.pack(
'!B', self.
length)
513 self.
header = b
'\xFA\xFF\x32\xFF' + struct.pack(
'!H', self.
length)
517 """Get the stored position of the device. 518 It is used internally for local magnetic declination and local gravity. 523 lat, lon, alt = struct.unpack(
'!ddd', data)
524 elif len(data) == 12:
525 lat, lon, alt = struct.unpack(
'!fff', data)
527 raise MTException(
'Could not parse ReqLatLonAltAck message: wrong' 529 return (lat, lon, alt)
532 """Set the position of the device. 533 It is used internally for local magnetic declination and local gravity. 536 data = struct.pack(
'!ddd', lat, lon, alt)
540 """Get the available XKF scenarios on the device.""" 542 data = self.
write_ack(MID.ReqAvailableScenarios)
545 for i
in range(len(data)/22):
546 scenario_type, version, label =\
547 struct.unpack(
'!BB20s', data[22*i:22*(i+1)])
548 scenarios.append((scenario_type, version, label.strip()))
552 raise MTException(
"could not parse the available XKF scenarios.")
556 """Get the ID of the currently used XKF scenario.""" 558 data = self.
write_ack(MID.SetCurrentScenario)
563 """Sets the XKF scenario to use.""" 565 data = struct.pack(
'!BB', 0, scenario_id)
566 self.
write_ack(MID.SetCurrentScenario, data)
569 """Reset the orientation. 571 Code can take several values: 572 0x0000: store current settings (only in config mode), 573 0x0001: heading reset (NOT supported by MTi-G), 574 0x0003: object reset. 576 data = struct.pack(
'!H', code)
577 self.
write_ack(MID.ResetOrientation, data)
580 """Initiate the "no rotation" procedure to estimate gyro biases.""" 582 data = struct.pack(
'!H', duration)
586 """Get UTC time from device.""" 589 ns, year, month, day, hour, minute, second, flag = \
590 struct.unpack(
'!IHBBBBBB', data)
591 return (ns, year, month, day, hour, minute, second, flag)
593 def SetUTCTime(self, ns, year, month, day, hour, minute, second, flag):
594 """Set UTC time on the device.""" 596 data = struct.pack(
'!IHBBBBBB', ns, year, month, day, hour, minute,
601 """Adjust UTC Time of device using correction ticks (0.1 ms).""" 603 data = struct.pack(
'!i', ticks)
604 self.write(MID.AdjustUTCTime, data)
610 """Configure the mode and settings of the MT device in legacy mode.""" 614 except MTErrorMessage
as e:
620 except MTException
as e:
622 print "no ack received while switching from MTData2 to MTData." 626 if period
is not None:
628 if skipfactor
is not None:
633 """Read configuration from device in legacy mode.""" 642 if mid == MID.MTData:
644 elif mid == MID.MTData2:
647 raise MTException(
"unknown data message: mid=0x%02X (%s)." %
652 def parse_temperature(data_id, content, ffmt):
654 if (data_id & 0x00F0) == 0x10:
655 o[
'Temp'], = struct.unpack(
'!'+ffmt, content)
657 raise MTException(
"unknown packet: 0x%04X." % data_id)
660 def parse_timestamp(data_id, content, ffmt):
662 if (data_id & 0x00F0) == 0x10:
663 o[
'ns'], o[
'Year'], o[
'Month'], o[
'Day'], o[
'Hour'],\
664 o[
'Minute'], o[
'Second'], o[
'Flags'] =\
665 struct.unpack(
'!LHBBBBBB', content)
666 elif (data_id & 0x00F0) == 0x20:
667 o[
'PacketCounter'], = struct.unpack(
'!H', content)
668 elif (data_id & 0x00F0) == 0x30:
669 o[
'TimeOfWeek'], = struct.unpack(
'!L', content)
670 elif (data_id & 0x00F0) == 0x40:
671 o[
'gpsAge'], = struct.unpack(
'!B', content)
672 elif (data_id & 0x00F0) == 0x50:
673 o[
'pressureAge'], = struct.unpack(
'!B', content)
674 elif (data_id & 0x00F0) == 0x60:
675 o[
'SampleTimeFine'], = struct.unpack(
'!L', content)
676 elif (data_id & 0x00F0) == 0x70:
677 o[
'SampleTimeCoarse'], = struct.unpack(
'!L', content)
678 elif (data_id & 0x00F0) == 0x80:
679 o[
'startFrame'], o[
'endFrame'] = struct.unpack(
'!HH', content)
681 raise MTException(
"unknown packet: 0x%04X." % data_id)
684 def parse_orientation_data(data_id, content, ffmt):
686 if (data_id & 0x000C) == 0x00:
688 elif (data_id & 0x000C) == 0x04:
690 elif (data_id & 0x000C) == 0x08:
692 if (data_id & 0x00F0) == 0x10:
693 o[
'Q0'], o[
'Q1'], o[
'Q2'], o[
'Q3'] = struct.unpack(
'!'+4*ffmt,
695 elif (data_id & 0x00F0) == 0x20:
696 o[
'a'], o[
'b'], o[
'c'], o[
'd'], o[
'e'], o[
'f'], o[
'g'], o[
'h'],\
697 o[
'i'] = struct.unpack(
'!'+9*ffmt, content)
698 elif (data_id & 0x00F0) == 0x30:
699 o[
'Roll'], o[
'Pitch'], o[
'Yaw'] = struct.unpack(
'!'+3*ffmt,
702 raise MTException(
"unknown packet: 0x%04X." % data_id)
705 def parse_pressure(data_id, content, ffmt):
707 if (data_id & 0x00F0) == 0x10:
708 o[
'Pressure'], = struct.unpack(
'!L', content)
710 raise MTException(
"unknown packet: 0x%04X." % data_id)
713 def parse_acceleration(data_id, content, ffmt):
715 if (data_id & 0x000C) == 0x00:
717 elif (data_id & 0x000C) == 0x04:
719 elif (data_id & 0x000C) == 0x08:
721 if (data_id & 0x00F0) == 0x10:
722 o[
'Delta v.x'], o[
'Delta v.y'], o[
'Delta v.z'] = \
723 struct.unpack(
'!'+3*ffmt, content)
724 elif (data_id & 0x00F0) == 0x20:
725 o[
'accX'], o[
'accY'], o[
'accZ'] = \
726 struct.unpack(
'!'+3*ffmt, content)
727 elif (data_id & 0x00F0) == 0x30:
728 o[
'freeAccX'], o[
'freeAccY'], o[
'freeAccZ'] = \
729 struct.unpack(
'!'+3*ffmt, content)
730 elif (data_id & 0x00F0) == 0x40:
731 o[
'accX'], o[
'accY'], o[
'accZ'] = \
732 struct.unpack(
'!'+3*ffmt, content)
734 raise MTException(
"unknown packet: 0x%04X." % data_id)
737 def parse_position(data_id, content, ffmt):
739 if (data_id & 0x000C) == 0x00:
741 elif (data_id & 0x000C) == 0x04:
743 elif (data_id & 0x000C) == 0x08:
745 if (data_id & 0x00F0) == 0x10:
746 o[
'altMsl'], = struct.unpack(
'!'+ffmt, content)
747 elif (data_id & 0x00F0) == 0x20:
748 o[
'altEllipsoid'], = struct.unpack(
'!'+ffmt, content)
749 elif (data_id & 0x00F0) == 0x30:
750 o[
'ecefX'], o[
'ecefY'], o[
'ecefZ'] = \
751 struct.unpack(
'!'+3*ffmt, content)
752 elif (data_id & 0x00F0) == 0x40:
753 o[
'lat'], o[
'lon'] = struct.unpack(
'!'+2*ffmt, content)
755 raise MTException(
"unknown packet: 0x%04X." % data_id)
758 def parse_GNSS(data_id, content, ffmt):
760 if (data_id & 0x00F0) == 0x10:
761 o[
'itow'], o[
'year'], o[
'month'], o[
'day'], o[
'hour'],\
762 o[
'min'], o[
'sec'], o[
'valid'], o[
'tAcc'], o[
'nano'],\
763 o[
'fixtype'], o[
'flags'], o[
'numSV'], o[
'lon'], o[
'lat'],\
764 o[
'height'], o[
'hMSL'], o[
'hAcc'], o[
'vAcc'], o[
'velN'],\
765 o[
'velE'], o[
'velD'], o[
'gSpeed'], o[
'headMot'], o[
'sAcc'],\
766 o[
'headAcc'], o[
'headVeh'], o[
'gdop'], o[
'pdop'],\
767 o[
'tdop'], o[
'vdop'], o[
'hdop'], o[
'ndop'], o[
'edop'] = \
768 struct.unpack(
'!IHBBBBBBIiBBBxiiiiIIiiiiiIIiHHHHHHH',
782 elif (data_id & 0x00F0) == 0x20:
783 o[
'iTOW'], o[
'numSvs'] = struct.unpack(
'!LBxxx', content[:8])
786 for i
in range(o[
'numSvs']):
787 ch[
'gnssId'], ch[
'svId'], ch[
'cno'], ch[
'flags'] = \
788 struct.unpack(
'!BBBB', content[8+4*i:12+4*i])
792 raise MTException(
"unknown packet: 0x%04X." % data_id)
795 def parse_angular_velocity(data_id, content, ffmt):
797 if (data_id & 0x000C) == 0x00:
799 elif (data_id & 0x000C) == 0x04:
801 elif (data_id & 0x000C) == 0x08:
803 if (data_id & 0x00F0) == 0x20:
804 o[
'gyrX'], o[
'gyrY'], o[
'gyrZ'] = \
805 struct.unpack(
'!'+3*ffmt, content)
806 elif (data_id & 0x00F0) == 0x30:
807 o[
'Delta q0'], o[
'Delta q1'], o[
'Delta q2'], o[
'Delta q3'] = \
808 struct.unpack(
'!'+4*ffmt, content)
809 elif (data_id & 0x00F0) == 0x40:
810 o[
'gyrX'], o[
'gyrY'], o[
'gyrZ'] = \
811 struct.unpack(
'!'+3*ffmt, content)
813 raise MTException(
"unknown packet: 0x%04X." % data_id)
816 def parse_GPS(data_id, content, ffmt):
818 if (data_id & 0x00F0) == 0x30:
819 o[
'iTOW'], g, p, t, v, h, n, e = \
820 struct.unpack(
'!LHHHHHHH', content)
821 o[
'gDOP'], o[
'pDOP'], o[
'tDOP'], o[
'vDOP'], o[
'hDOP'], \
822 o[
'nDOP'], o[
'eDOP'] = 0.01*g, 0.01*p, 0.01*t, \
823 0.01*v, 0.01*h, 0.01*n, 0.01*e
824 elif (data_id & 0x00F0) == 0x40:
825 o[
'iTOW'], o[
'fTOW'], o[
'Week'], o[
'gpsFix'], o[
'Flags'], \
826 o[
'ecefX'], o[
'ecefY'], o[
'ecefZ'], o[
'pAcc'], \
827 o[
'ecefVX'], o[
'ecefVY'], o[
'ecefVZ'], o[
'sAcc'], \
828 o[
'pDOP'], o[
'numSV'] = \
829 struct.unpack(
'!LlhBBlllLlllLHxBx', content)
832 elif (data_id & 0x00F0) == 0x80:
833 o[
'iTOW'], o[
'tAcc'], o[
'nano'], o[
'year'], o[
'month'], \
834 o[
'day'], o[
'hour'], o[
'min'], o[
'sec'], o[
'valid'] = \
835 struct.unpack(
'!LLlHBBBBBB', content)
836 elif (data_id & 0x00F0) == 0xA0:
837 o[
'iTOW'], o[
'numCh'] = struct.unpack(
'!LBxxx', content[:8])
840 for i
in range(o[
'numCh']):
841 ch[
'chn'], ch[
'svid'], ch[
'flags'], ch[
'quality'], \
842 ch[
'cno'], ch[
'elev'], ch[
'azim'], ch[
'prRes'] = \
843 struct.unpack(
'!BBBBBbhl', content[8+12*i:20+12*i])
845 o[
'channels'] = channels
847 raise MTException(
"unknown packet: 0x%04X." % data_id)
850 def parse_SCR(data_id, content, ffmt):
852 if (data_id & 0x00F0) == 0x10:
853 o[
'accX'], o[
'accY'], o[
'accZ'], o[
'gyrX'], o[
'gyrY'], \
854 o[
'gyrZ'], o[
'magX'], o[
'magY'], o[
'magZ'], o[
'Temp'] = \
855 struct.unpack(
"!9Hh", content)
856 elif (data_id & 0x00F0) == 0x20:
857 o[
'tempGyrX'], o[
'tempGyrY'], o[
'tempGyrZ'] = \
858 struct.unpack(
"!hhh", content)
860 raise MTException(
"unknown packet: 0x%04X." % data_id)
863 def parse_analog_in(data_id, content, ffmt):
865 if (data_id & 0x00F0) == 0x10:
866 o[
'analogIn1'], = struct.unpack(
"!H", content)
867 elif (data_id & 0x00F0) == 0x20:
868 o[
'analogIn2'], = struct.unpack(
"!H", content)
870 raise MTException(
"unknown packet: 0x%04X." % data_id)
873 def parse_magnetic(data_id, content, ffmt):
875 if (data_id & 0x000C) == 0x00:
877 elif (data_id & 0x000C) == 0x04:
879 elif (data_id & 0x000C) == 0x08:
881 if (data_id & 0x00F0) == 0x20:
882 o[
'magX'], o[
'magY'], o[
'magZ'] = \
883 struct.unpack(
"!3"+ffmt, content)
885 raise MTException(
"unknown packet: 0x%04X." % data_id)
888 def parse_velocity(data_id, content, ffmt):
890 if (data_id & 0x000C) == 0x00:
892 elif (data_id & 0x000C) == 0x04:
894 elif (data_id & 0x000C) == 0x08:
896 if (data_id & 0x00F0) == 0x10:
897 o[
'velX'], o[
'velY'], o[
'velZ'] = \
898 struct.unpack(
"!3"+ffmt, content)
900 raise MTException(
"unknown packet: 0x%04X." % data_id)
903 def parse_status(data_id, content, ffmt):
905 if (data_id & 0x00F0) == 0x10:
906 o[
'StatusByte'], = struct.unpack(
"!B", content)
907 elif (data_id & 0x00F0) == 0x20:
908 o[
'StatusWord'], = struct.unpack(
"!L", content)
909 elif (data_id & 0x00F0) == 0x40:
910 o[
'RSSI'], = struct.unpack(
"!b", content)
912 raise MTException(
"unknown packet: 0x%04X." % data_id)
919 data_id, size = struct.unpack(
'!HB', data[:3])
920 if (data_id & 0x0003) == 0x3:
922 elif (data_id & 0x0003) == 0x0:
925 raise MTException(
"fixed point precision not supported.")
926 content = data[3:3+size]
928 group = data_id & 0xF800
930 if group == XDIGroup.Temperature:
931 output.setdefault(
'Temperature', {}).update(
932 parse_temperature(data_id, content, ffmt))
933 elif group == XDIGroup.Timestamp:
934 output.setdefault(
'Timestamp', {}).update(
935 parse_timestamp(data_id, content, ffmt))
936 elif group == XDIGroup.OrientationData:
937 output.setdefault(
'Orientation Data', {}).update(
938 parse_orientation_data(data_id, content, ffmt))
939 elif group == XDIGroup.Pressure:
940 output.setdefault(
'Pressure', {}).update(
941 parse_pressure(data_id, content, ffmt))
942 elif group == XDIGroup.Acceleration:
943 output.setdefault(
'Acceleration', {}).update(
944 parse_acceleration(data_id, content, ffmt))
945 elif group == XDIGroup.Position:
946 output.setdefault(
'Position', {}).update(
947 parse_position(data_id, content, ffmt))
948 elif group == XDIGroup.GNSS:
949 output.setdefault(
'GNSS', {}).update(
950 parse_GNSS(data_id, content, ffmt))
951 elif group == XDIGroup.AngularVelocity:
952 output.setdefault(
'Angular Velocity', {}).update(
953 parse_angular_velocity(data_id, content, ffmt))
954 elif group == XDIGroup.GPS:
955 output.setdefault(
'GPS', {}).update(
956 parse_GPS(data_id, content, ffmt))
957 elif group == XDIGroup.SensorComponentReadout:
958 output.setdefault(
'SCR', {}).update(
959 parse_SCR(data_id, content, ffmt))
960 elif group == XDIGroup.AnalogIn:
961 output.setdefault(
'Analog In', {}).update(
962 parse_analog_in(data_id, content, ffmt))
963 elif group == XDIGroup.Magnetic:
964 output.setdefault(
'Magnetic', {}).update(
965 parse_magnetic(data_id, content, ffmt))
966 elif group == XDIGroup.Velocity:
967 output.setdefault(
'Velocity', {}).update(
968 parse_velocity(data_id, content, ffmt))
969 elif group == XDIGroup.Status:
970 output.setdefault(
'Status', {}).update(
971 parse_status(data_id, content, ffmt))
973 raise MTException(
"unknown XDI group: 0x%04X." % group)
975 raise MTException(
"couldn't parse MTData2 message.")
979 """Read and parse a legacy measurement packet.""" 989 if mode & OutputMode.RAW:
991 o[
'accX'], o[
'accY'], o[
'accZ'], o[
'gyrX'], o[
'gyrY'], \
992 o[
'gyrZ'], o[
'magX'], o[
'magY'], o[
'magZ'], o[
'temp'] =\
993 struct.unpack(
'!10H', data[:20])
997 if mode & OutputMode.RAWGPS:
999 o[
'Press'], o[
'bPrs'], o[
'ITOW'], o[
'LAT'], o[
'LON'], o[
'ALT'],\
1000 o[
'VEL_N'], o[
'VEL_E'], o[
'VEL_D'], o[
'Hacc'], o[
'Vacc'],\
1001 o[
'Sacc'], o[
'bGPS'] = struct.unpack(
'!HBI6i3IB', data[:44])
1003 output[
'RAWGPS'] = o
1005 if mode & OutputMode.Temp:
1006 temp, = struct.unpack(
'!f', data[:4])
1008 output[
'Temp'] = temp
1010 if mode & OutputMode.Calib:
1012 if (settings & OutputSettings.Coordinates_NED):
1016 if not (settings & OutputSettings.CalibMode_GyrMag):
1017 o[
'accX'], o[
'accY'], o[
'accZ'] = struct.unpack(
'!3f',
1020 if not (settings & OutputSettings.CalibMode_AccMag):
1021 o[
'gyrX'], o[
'gyrY'], o[
'gyrZ'] = struct.unpack(
'!3f',
1024 if not (settings & OutputSettings.CalibMode_AccGyr):
1025 o[
'magX'], o[
'magY'], o[
'magZ'] = struct.unpack(
'!3f',
1030 if mode & OutputMode.Orient:
1032 if (settings & OutputSettings.Coordinates_NED):
1036 if settings & OutputSettings.OrientMode_Euler:
1037 o[
'roll'], o[
'pitch'], o[
'yaw'] = struct.unpack(
'!3f',
1040 elif settings & OutputSettings.OrientMode_Matrix:
1041 a, b, c, d, e, f, g, h, i = struct.unpack(
'!9f',
1044 o[
'matrix'] = ((a, b, c), (d, e, f), (g, h, i))
1046 q0, q1, q2, q3 = struct.unpack(
'!4f', data[:16])
1048 o[
'quaternion'] = (q0, q1, q2, q3)
1049 output[
'Orient'] = o
1051 if mode & OutputMode.Auxiliary:
1053 if not (settings & OutputSettings.AuxiliaryMode_NoAIN1):
1054 o[
'Ain_1'], = struct.unpack(
'!H', data[:2])
1056 if not (settings & OutputSettings.AuxiliaryMode_NoAIN2):
1057 o[
'Ain_2'], = struct.unpack(
'!H', data[:2])
1059 output[
'Auxiliary'] = o
1061 if mode & OutputMode.Position:
1063 o[
'Lat'], o[
'Lon'], o[
'Alt'] = struct.unpack(
'!3f', data[:12])
1067 if mode & OutputMode.Velocity:
1069 if (settings & OutputSettings.Coordinates_NED):
1073 o[
'Vel_X'], o[
'Vel_Y'], o[
'Vel_Z'] = struct.unpack(
'!3f',
1078 if mode & OutputMode.Status:
1079 status, = struct.unpack(
'!B', data[:1])
1081 output[
'Stat'] = status
1083 if settings & OutputSettings.Timestamp_SampleCnt:
1084 TS, = struct.unpack(
'!H', data[:2])
1086 output[
'Sample'] = TS
1088 if settings & OutputSettings.Timestamp_UTCTime:
1090 o[
'ns'], o[
'Year'], o[
'Month'], o[
'Day'], o[
'Hour'],\
1091 o[
'Minute'], o[
'Second'], o[
'Flags'] = struct.unpack(
1092 '!ihbbbbb', data[:12])
1094 output[
'Timestamp'] = o
1096 except struct.error, e:
1097 raise MTException(
"could not parse MTData message.")
1099 raise MTException(
"could not parse MTData message (too long).")
1103 """Change the baudrate, reset the device and reopen communication.""" 1104 brid = Baudrates.get_BRID(baudrate)
1108 self.device.baudrate = baudrate
1120 for port
in glob.glob(
"/dev/tty*S*"):
1122 print "Trying '%s'" % port
1126 mtdev_list.append((port, br))
1136 baudrates = (115200, 460800, 921600, 230400, 57600, 38400, 19200, 9600)
1137 for br
in baudrates:
1139 print "Trying %d bd:" % br,
1142 mt =
MTDevice(port, br, timeout=timeout, verbose=verbose,
1143 initial_wait=initial_wait)
1144 except serial.SerialException:
1146 print "fail: unable to open device." 1150 mt.GoToMeasurement()
1163 print """MT device driver. 1165 ./mtdevice.py [commands] [opts] 1169 Print this help and quit. 1171 Reset device to factory defaults. 1172 -a, --change-baudrate=NEW_BAUD 1173 Change baudrate from BAUD (see below) to NEW_BAUD. 1174 -c, --configure=OUTPUT 1175 Configure the device (see OUTPUT description below). 1177 Print MTData. It is the default if no other command is supplied. 1179 Print current MT device configuration. 1180 -x, --xkf-scenario=ID 1181 Change the current XKF scenario. 1182 -l, --legacy-configure 1183 Configure the device in legacy mode (needs MODE and SETTINGS arguments 1187 -y, --synchronization=settings (see below) 1188 Configure the synchronization settings of each sync line (see below) 1189 -u, --setUTCTime=time (see below) 1190 Sets the UTC time buffer of the device 1194 Serial interface of the device (default: /dev/ttyUSB0). If 'auto', then 1195 all serial ports are tested at all baudrates and the first 1196 suitable device is used. 1198 Baudrate of serial interface (default: 115200). If 0, then all 1199 rates are tried until a suitable one is found. 1200 -t, --timeout=TIMEOUT 1201 Timeout of serial communication in second (default: 0.002). 1202 -w, --initial-wait=WAIT 1203 Initial wait to allow device to be ready in second (default: 0.1). 1205 Configuration option: 1207 The format is a sequence of "<group><type><frequency>?<format>?" 1208 separated by commas. 1209 The frequency and format are optional. 1210 The groups and types can be: 1211 t temperature (max frequency: 1 Hz): 1213 i timestamp (max frequency: 2000 Hz): 1216 ii Integer Time of the Week (ITOW) 1218 ic sample time coarse 1220 o orientation data (max frequency: 400 Hz): 1224 b pressure (max frequency: 50 Hz): 1226 a acceleration (max frequency: 2000 Hz (see documentation)): 1229 af free acceleration 1230 ah acceleration HR (max frequency 1000 Hz) 1231 p position (max frequency: 400 Hz): 1232 pa altitude ellipsoid 1234 pl latitude longitude 1235 n GNSS (max frequency: 4 Hz): 1237 ns GNSS satellites info 1238 w angular velocity (max frequency: 2000 Hz (see documentation)): 1241 wh rate of turn HR (max frequency 1000 Hz) 1242 g GPS (max frequency: 4 Hz): 1247 r Sensor Component Readout (max frequency: 2000 Hz): 1248 rr ACC, GYR, MAG, temperature 1249 rt Gyro temperatures 1250 m Magnetic (max frequency: 100 Hz): 1252 v Velocity (max frequency: 400 Hz): 1254 s Status (max frequency: 2000 Hz): 1257 Frequency is specified in decimal and is assumed to be the maximum 1258 frequency if it is omitted. 1259 Format is a combination of the precision for real valued numbers and 1262 f single precision floating point number (32-bit) (default) 1263 d double precision floating point number (64-bit) 1265 e East-North-Up (default) 1269 The default configuration for the MTi-1/10/100 IMUs can be 1270 specified either as: 1273 "wd2000fe,ad2000fe,mf100fe,ip2000,if2000,sw2000" 1274 For getting quaternion orientation in float with sample time: 1276 For longitude, latitude, altitude and orientation (on MTi-G-700): 1277 "pl400fe,pa400fe,oq400fe" 1279 Synchronization settings: 1280 The format follows the xsens protocol documentation. All fields are required 1281 and separated by commas. 1282 Note: The entire synchronization buffer is wiped every time a new one 1283 is set, so it is necessary to specify the settings of multiple 1285 It also possible to clear the synchronization with the argument "clear" 1287 Function (see manual for details): 1288 3 Trigger indication 1289 4 Interval Transition Measurement 1291 9 ClockBiasEstimation 1293 Line (manual for details): 1295 1 GPSClockIn (only available for 700/710) 1296 2 Input Line (SyncIn) 1298 5 ExtTimepulseIn (only available for 700/710) 1299 6 Software (only available for SendLatest with ReqData message) 1301 1 Positive pulse/ Rising edge 1302 2 Negative pulse/ Falling edge 1307 Skip First (unsigned_int): 1308 Number of initial events to skip before taking actions 1309 Skip Factor (unsigned_int): 1310 Number of events to skip before taking action again 1311 Ignored with ReqData. 1312 Pulse Width (unsigned_int): 1314 For SyncOut, the width of the generated pulse in 100 microseconds 1315 unit. Ignored for Toggle pulses. 1317 Delay after receiving a sync pulse to taking action, 1318 100 microseconds units, range [0...600000] 1320 Reference clock period in milliseconds for ClockBiasEstimation 1322 Offset from event to pulse generation. 1323 100 microseconds unit, range [-30000...+30000] 1326 For changing the sync setting of the SyncIn line to trigger indication 1327 with rising edge, one time triggering and no skipping and delay. Enter 1331 Note a number is still in the place for pulse width despite it being 1334 To set multiple lines at once: 1335 ./mtdevice.py -y 3,2,1,0,0,0,0,0 -y 9,0,1,0,0,0,10,0 1337 To clear the synchronization settings of MTi 1338 ./mtdevice.py -y clear 1340 SetUTCTime settings: 1341 There are two ways to set the UTCtime for the MTi. 1342 Option #1: set MTi to the current UTC time based on local system time with 1344 Option #2: set MTi to a specified UTC time 1345 The time fields are set as follows: 1346 year: range [1999,2099] 1348 day: day of the month, range [1,31] 1349 hour: hour of the day, range [0,23] 1350 min: minute of the hour, range [0,59] 1351 sec: second of the minute, range [0,59] 1352 ns: nanosecond of the second, range [0,1000000000] 1354 1: Valid Time of Week 1355 2: Valid Week Number 1357 Note: the flag is ignored for setUTCTime as it is set by the module 1358 itself when connected to a GPS 1361 Set UTC time for the device: 1362 ./mtdevice.py -u now 1363 ./mtdevice.py -u 1999,1,1,0,0,0,0,0 1366 -m, --output-mode=MODE 1367 Legacy mode of the device to select the information to output. 1368 This is required for 'legacy-configure' command. 1369 MODE can be either the mode value in hexadecimal, decimal or 1370 binary form, or a string composed of the following characters 1372 t temperature, [0x0001] 1373 c calibrated data, [0x0002] 1374 o orientation data, [0x0004] 1375 a auxiliary data, [0x0008] 1376 p position data (requires MTi-G), [0x0010] 1377 v velocity data (requires MTi-G), [0x0020] 1378 s status data, [0x0800] 1379 g raw GPS mode (requires MTi-G), [0x1000] 1380 r raw (incompatible with others except raw GPS), [0x4000] 1381 For example, use "--output-mode=so" to have status and 1383 -s, --output-settings=SETTINGS 1384 Legacy settings of the device. This is required for 'legacy-configure' 1386 SETTINGS can be either the settings value in hexadecimal, 1387 decimal or binary form, or a string composed of the following 1388 characters (in any order): 1389 t sample count (excludes 'n') 1390 n no sample count (excludes 't') 1392 q orientation in quaternion (excludes 'e' and 'm') 1393 e orientation in Euler angles (excludes 'm' and 'q') 1394 m orientation in matrix (excludes 'q' and 'e') 1395 A acceleration in calibrated data 1396 G rate of turn in calibrated data 1397 M magnetic field in calibrated data 1398 i only analog input 1 (excludes 'j') 1399 j only analog input 2 (excludes 'i') 1400 N North-East-Down instead of default: X North Z up 1401 For example, use "--output-settings=tqMAG" for all calibrated 1402 data, sample counter and orientation in quaternion. 1404 Sampling period in (1/115200) seconds (default: 1152). 1405 Minimum is 225 (1.95 ms, 512 Hz), maximum is 1152 1407 Note that for legacy devices it is the period at which sampling occurs, 1408 not the period at which messages are sent (see below). 1411 -f, --deprecated-skip-factor=SKIPFACTOR 1412 Only for mark III devices. 1413 Number of samples to skip before sending MTData message 1415 The frequency at which MTData message is send is: 1416 115200/(PERIOD * (SKIPFACTOR + 1)) 1417 If the value is 0xffff, no data is send unless a ReqData request 1427 shopts =
'hra:c:eild:b:y:u:m:s:p:f:x:vt:w:' 1428 lopts = [
'help',
'reset',
'change-baudrate=',
'configure=',
'echo',
1429 'inspect',
'legacy-configure',
'device=',
'baudrate=',
1430 'output-mode=',
'output-settings=',
'period=',
1431 'deprecated-skip-factor=',
'xkf-scenario=',
'verbose',
1432 'synchronization=',
'setUTCtime=',
'timeout=',
'initial-wait=']
1434 opts, args = getopt.gnu_getopt(sys.argv[1:], shopts, lopts)
1435 except getopt.GetoptError, e:
1440 device =
'/dev/ttyUSB0' 1456 if o
in (
'-h',
'--help'):
1459 elif o
in (
'-r',
'--reset'):
1460 actions.append(
'reset')
1461 elif o
in (
'-a',
'--change-baudrate'):
1463 new_baudrate = int(a)
1465 print "change-baudrate argument must be integer." 1467 actions.append(
'change-baudrate')
1468 elif o
in (
'-c',
'--configure'):
1470 if output_config
is None:
1472 actions.append(
'configure')
1473 elif o
in (
'-e',
'--echo'):
1474 actions.append(
'echo')
1475 elif o
in (
'-i',
'--inspect'):
1476 actions.append(
'inspect')
1477 elif o
in (
'-l',
'--legacy-configure'):
1478 actions.append(
'legacy-configure')
1479 elif o
in (
'-x',
'--xkf-scenario'):
1483 print "xkf-scenario argument must be integer." 1485 actions.append(
'xkf-scenario')
1486 elif o
in (
'-y',
'--synchronization'):
1488 if new_sync_settings
is None:
1490 sync_settings.append(new_sync_settings)
1491 actions.append(
'synchronization')
1492 elif o
in (
'-u',
'--setUTCtime'):
1494 if UTCtime_settings
is None:
1496 actions.append(
'setUTCtime')
1497 elif o
in (
'-d',
'--device'):
1499 elif o
in (
'-b',
'--baudrate'):
1503 print "baudrate argument must be integer." 1505 elif o
in (
'-m',
'--output-mode'):
1509 elif o
in (
'-s',
'--output-settings'):
1511 if settings
is None:
1513 elif o
in (
'-p',
'--period'):
1517 print "period argument must be integer." 1519 elif o
in (
'-f',
'--deprecated-skip-factor'):
1523 print "skip-factor argument must be integer." 1525 elif o
in (
'-v',
'--verbose'):
1527 elif o
in (
'-t',
'--timeout'):
1531 print "timeout argument must be a floating number." 1533 elif o
in (
'-w',
'--initial-wait'):
1535 initial_wait = float(a)
1537 print "initial-wait argument must be a floating number." 1541 if len(actions) == 0:
1542 actions.append(
'echo')
1544 if device ==
'auto':
1546 initial_wait=initial_wait)
1548 print "Detected devices:",
"".join(
'\n\t%s @ %d' % (d, p)
1550 print "Using %s @ %d" % devs[0]
1551 device, baudrate = devs[0]
1553 print "No suitable device found." 1557 baudrate =
find_baudrate(device, timeout=timeout, verbose=verbose,
1558 initial_wait=initial_wait)
1560 print "No suitable baudrate found." 1564 mt =
MTDevice(device, baudrate, timeout=timeout, verbose=verbose,
1565 initial_wait=initial_wait)
1566 except serial.SerialException:
1569 if 'inspect' in actions:
1571 if 'change-baudrate' in actions:
1572 print "Changing baudrate from %d to %d:" % (baudrate, new_baudrate),
1574 mt.ChangeBaudrate(new_baudrate)
1576 if 'reset' in actions:
1577 print "Restoring factory defaults",
1579 mt.RestoreFactoryDefaults()
1581 if 'configure' in actions:
1582 print "Changing output configuration",
1584 mt.SetOutputConfiguration(output_config)
1586 if 'synchronization' in actions:
1587 print "Changing synchronization settings",
1589 mt.SetSyncSettings(sync_settings)
1591 if 'setUTCtime' in actions:
1592 print "Setting UTC time in the device",
1594 mt.SetUTCTime(UTCtime_settings[6],
1595 UTCtime_settings[0],
1596 UTCtime_settings[1],
1597 UTCtime_settings[2],
1598 UTCtime_settings[3],
1599 UTCtime_settings[4],
1600 UTCtime_settings[5],
1601 UTCtime_settings[7])
1603 if 'legacy-configure' in actions:
1605 print "output-mode is require to configure the device in "\
1608 if settings
is None:
1609 print "output-settings is required to configure the device in "\
1612 print "Configuring in legacy mode",
1614 mt.configure_legacy(mode, settings, period, skipfactor)
1616 if 'xkf-scenario' in actions:
1617 print "Changing XKF scenario",
1619 mt.SetCurrentScenario(new_xkf)
1621 if 'echo' in actions:
1627 print mt.read_measurement(mode, settings)
1628 except KeyboardInterrupt:
1630 except MTErrorMessage
as e:
1631 print "MTErrorMessage:", e
1632 except MTException
as e:
1633 print "MTException:", e
1638 def config_fmt(config):
1639 """Hexadecimal configuration.""" 1640 return '[%s]' %
', '.join(
'(0x%04X, %d)' % (mode, freq)
1641 for (mode, freq)
in config)
1643 def hex_fmt(size=4):
1644 """Factory for hexadecimal representation formatter.""" 1645 fmt =
'0x%%0%dX' % (2*size)
1648 """Hexadecimal representation.""" 1653 def sync_fmt(settings):
1654 """Synchronization settings: N*12 bytes""" 1655 return '[%s]' %
', '.join(
'(0x%02X, 0x%02X, 0x%02X, 0x%02X,' 1656 ' 0x%04X, 0x%04X, 0x%04X, 0x%04X)' % s
1659 def try_message(m, f, formater=None, *args, **kwargs):
1662 if formater
is not None:
1663 print formater(f(*args, **kwargs))
1665 pprint.pprint(f(*args, **kwargs), indent=4)
1666 except MTTimeoutException
as e:
1667 print 'timeout: might be unsupported by your device.' 1668 except MTErrorMessage
as e:
1670 print 'message unsupported by your device.' 1673 print "Device: %s at %d Bd:" % (device, baudrate)
1674 try_message(
"device ID:", mt.GetDeviceID, hex_fmt(4))
1675 try_message(
"product code:", mt.GetProductCode)
1676 try_message(
"firmware revision:", mt.GetFirmwareRev)
1677 try_message(
"baudrate:", mt.GetBaudrate)
1678 try_message(
"error mode:", mt.GetErrorMode, hex_fmt(2))
1679 try_message(
"option flags:", mt.GetOptionFlags, hex_fmt(4))
1680 try_message(
"location ID:", mt.GetLocationID, hex_fmt(2))
1681 try_message(
"transmit delay:", mt.GetTransmitDelay)
1682 try_message(
"synchronization settings:", mt.GetSyncSettings, sync_fmt)
1683 try_message(
"general configuration:", mt.GetConfiguration)
1684 try_message(
"output configuration (mark IV devices):",
1685 mt.GetOutputConfiguration, config_fmt)
1686 try_message(
"string output type:", mt.GetStringOutputType)
1687 try_message(
"period:", mt.GetPeriod)
1688 try_message(
"alignment rotation sensor:", mt.GetAlignmentRotation,
1690 try_message(
"alignment rotation local:", mt.GetAlignmentRotation,
1692 try_message(
"output mode:", mt.GetOutputMode, hex_fmt(2))
1693 try_message(
"extended output mode:", mt.GetExtOutputMode, hex_fmt(2))
1694 try_message(
"output settings:", mt.GetOutputSettings, hex_fmt(4))
1695 try_message(
"GPS coordinates (lat, lon, alt):", mt.GetLatLonAlt)
1696 try_message(
"available scenarios:", mt.GetAvailableScenarios)
1697 try_message(
"current scenario ID:", mt.GetCurrentScenario)
1698 try_message(
"UTC time:", mt.GetUTCTime)
1702 """Parse the mark IV output configuration argument.""" 1706 'iu': (0x1010, 2000),
1707 'ip': (0x1020, 2000),
1708 'ii': (0x1030, 2000),
1709 'if': (0x1060, 2000),
1710 'ic': (0x1070, 2000),
1711 'ir': (0x1080, 2000),
1712 'oq': (0x2010, 400),
1713 'om': (0x2020, 400),
1714 'oe': (0x2030, 400),
1716 'ad': (0x4010, 2000),
1717 'aa': (0x4020, 2000),
1718 'af': (0x4030, 2000),
1719 'ah': (0x4040, 1000),
1720 'pa': (0x5020, 400),
1721 'pp': (0x5030, 400),
1722 'pl': (0x5040, 400),
1725 'wr': (0x8020, 2000),
1726 'wd': (0x8030, 2000),
1727 'wh': (0x8040, 1000),
1732 'rr': (0xA010, 2000),
1733 'rt': (0xA020, 2000),
1734 'mf': (0xC020, 100),
1735 'vv': (0xD010, 400),
1736 'sb': (0xE010, 2000),
1737 'sw': (0xE020, 2000)
1740 format_dict = {
'f': 0x00,
'd': 0x03,
'e': 0x00,
'n': 0x04,
'w': 0x08}
1741 config_re = re.compile(
'([a-z]{2})(\d+)?([fdenw])?([fdnew])?')
1742 output_configuration = []
1744 for item
in config_arg.split(
','):
1745 group, frequency, fmt1, fmt2 = config_re.findall(item.lower())[0]
1746 code, max_freq = code_dict[group]
1747 if fmt1
in format_dict:
1748 code |= format_dict[fmt1]
1749 if fmt2
in format_dict:
1750 code |= format_dict[fmt2]
1752 frequency = min(max_freq, int(frequency))
1754 frequency = max_freq
1755 output_configuration.append((code, frequency))
1756 return output_configuration
1757 except (IndexError, KeyError):
1758 print 'could not parse output specification "%s"' % item
1763 """Parse command line output-mode argument.""" 1784 mode |= OutputMode.Temp
1786 mode |= OutputMode.Calib
1788 mode |= OutputMode.Orient
1790 mode |= OutputMode.Auxiliary
1792 mode |= OutputMode.Position
1794 mode |= OutputMode.Velocity
1796 mode |= OutputMode.Status
1798 mode |= OutputMode.RAWGPS
1800 mode |= OutputMode.RAW 1802 print "Unknown output-mode specifier: '%s'" % c
1808 """Parse command line output-settings argument.""" 1816 settings = int(arg, 2)
1821 settings = int(arg, 16)
1828 calib_mode = OutputSettings.CalibMode_Mask
1832 timestamp = OutputSettings.Timestamp_SampleCnt
1834 timestamp = OutputSettings.Timestamp_None
1836 timestamp |= OutputSettings.Timestamp_UTCTime 1838 orient_mode = OutputSettings.OrientMode_Quaternion
1840 orient_mode = OutputSettings.OrientMode_Euler
1842 orient_mode = OutputSettings.OrientMode_Matrix
1844 calib_mode &= OutputSettings.CalibMode_Acc
1846 calib_mode &= OutputSettings.CalibMode_Gyr
1848 calib_mode &= OutputSettings.CalibMode_Mag
1850 calib_mode &= OutputSettings.AuxiliaryMode_NoAIN2
1852 calib_mode &= OutputSettings.AuxiliaryMode_NoAIN1
1854 NED = OutputSettings.Coordinates_NED
1856 print "Unknown output-settings specifier: '%s'" % c
1858 settings = timestamp | orient_mode | calib_mode | NED
1862 """Parse command line synchronization-settings argument.""" 1864 sync_settings = [0,0,0,0,0,0,0,0]
1865 return sync_settings
1868 sync_settings = arg.split(
',')
1871 sync_settings = tuple([int(i)
for i
in sync_settings])
1873 print "Synchronization sync_settings must be integers." 1876 if sync_settings[0]
in (3, 4, 8, 9, 11)
and \
1877 sync_settings[1]
in (0, 1, 2, 4, 5, 6)
and \
1878 sync_settings[2]
in (1, 2, 3)
and \
1879 sync_settings[3]
in (0, 1):
1880 return sync_settings
1882 print "Invalid synchronization settings." 1890 timestamp = datetime.datetime.utcnow()
1892 time_settings.append(timestamp.year)
1893 time_settings.append(timestamp.month)
1894 time_settings.append(timestamp.day)
1895 time_settings.append(timestamp.hour)
1896 time_settings.append(timestamp.minute)
1897 time_settings.append(timestamp.second)
1898 time_settings.append(timestamp.microsecond*1000)
1899 time_settings.append(0)
1900 return time_settings
1903 time_settings = arg.split(
',')
1905 time_settings = [int(i)
for i
in time_settings]
1907 print "UTCtime settings must be integers." 1911 if 1999 <= time_settings[0] <= 2099
and\
1912 1 <= time_settings[1] <= 12
and\
1913 1 <= time_settings[2] <= 31
and\
1914 0 <= time_settings[3] <= 23
and\
1915 0 <= time_settings[4] <= 59
and\
1916 0 <= time_settings[5] <= 59
and\
1917 0 <= time_settings[6] <= 1000000000:
1918 return time_settings
1920 print "Invalid UTCtime settings." 1924 if __name__ ==
'__main__':
def SetPeriod(self, period)
def waitfor(self, size=1)
def GetOutputConfiguration(self)
def AdjustUTCTime(self, ticks)
def parse_MTData(self, data, mode=None, settings=None)
def GetOutputSettings(self)
def read_data_msg(self, buf=bytearray())
def ResetOrientation(self, code)
def _ensure_config_state(self)
def GetConfiguration(self)
def SetBaudrate(self, brid)
def SetUTCTime(self, ns, year, month, day, hour, minute, second, flag)
def GetSyncSettings(self)
def SetSyncSettings(self, sync_settings)
def SetNoRotation(self, duration)
def auto_config_legacy(self)
def SetOutputSkipFactor(self, skipfactor)
def SetOutputConfiguration(self, output_configuration)
def write_ack(self, mid, data=b'', n_retries=500)
def read_measurement(self, mode=None, settings=None)
def get_output_config(config_arg)
def find_baudrate(port, timeout=0.002, verbose=False, initial_wait=0.1)
Auto detect baudrate.
def SetOutputMode(self, mode)
def SetExtOutputMode(self, ext_mode)
def RestoreFactoryDefaults(self)
def GetStringOutputType(self)
def SetOptionFlags(self, set_flags, clear_flags)
def SetTransmitDelay(self, transmit_delay)
def GetCurrentScenario(self)
def SetAlignmentRotation(self, parameter, quaternion)
def ChangeBaudrate(self, baudrate)
def Reset(self, go_to_config=False)
High-level functions.
def __init__(self, port, baudrate=115200, timeout=0.002, autoconf=True, config_mode=False, verbose=False, initial_wait=0.1)
def write_msg(self, mid, data=b'')
Low-level communication.
def SetErrorMode(self, error_mode)
def GetTransmitDelay(self)
def find_devices(timeout=0.002, verbose=False, initial_wait=0.1)
def GetExtOutputMode(self)
def SetLocationID(self, location_id)
def SetLatLonAlt(self, lat, lon, alt)
def GoToMeasurement(self)
def _ensure_measurement_state(self)
def configure_legacy(self, mode, settings, period=None, skipfactor=None)
High-level utility functions.
def GetAlignmentRotation(self, parameter)
def inspect(mt, device, baudrate)
def usage()
Documentation for stand alone usage.
def get_synchronization_settings(arg)
def SetStringOutputType(self, string_output_type)
def GetAvailableScenarios(self)
def parse_MTData2(self, data)
def SetCurrentScenario(self, scenario_id)
def SetOutputSettings(self, settings)