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: "\
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 " 122 "and 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: "\
158 ' '.join(
"%02X" % v
for v
in data))
160 raise MTErrorMessage(data[0])
161 return (mid, buf[:-1])
165 def write_ack(self, mid, data=b'', n_resend=30, n_read=25):
166 """Send a message and read confirmation.""" 167 for _
in range(n_resend):
169 for _
in range(n_read):
171 if mid_ack == (mid+1):
174 print "ack (0x%02X) expected, got 0x%02X instead" % \
180 n_retries = n_resend*n_read
181 raise MTException(
"Ack (0x%02X) expected, MID 0x%02X received " 182 "instead (after %d retries)." % (mid+1, mid_ack,
187 """Switch device to config state if necessary.""" 188 if self.
state != DeviceState.Config:
192 """Switch device to measurement state if necessary.""" 193 if self.
state != DeviceState.Measurement:
199 def Reset(self, go_to_config=False):
202 If go_to_config then send WakeUpAck in order to leave the device in 209 if mid == MID.WakeUp:
211 self.
state = DeviceState.Config
213 self.
state = DeviceState.Measurement
216 """Place MT device in configuration mode.""" 218 self.
state = DeviceState.Config
221 """Place MT device in measurement mode.""" 224 self.
state = DeviceState.Measurement
227 """Get the device identifier.""" 230 deviceID, = struct.unpack(
'!I', data)
234 """Get the product code.""" 236 data = self.
write_ack(MID.ReqProductCode)
237 return str(data).strip()
240 """Get the hardware version.""" 242 data = self.
write_ack(MID.ReqHardwareVersion)
243 major, minor = struct.unpack(
'!BB', data)
244 return (major, minor)
247 """Get the firmware version.""" 251 major, minor, revision = struct.unpack(
'!BBB', data)
252 return (major, minor, revision)
255 major, minor, rev, buildnr, svnrev = struct.unpack(
'!BBBII', data)
256 return (major, minor, rev, buildnr, svnrev)
259 """Run the built-in self test.""" 262 bit_names = [
'accX',
'accY',
'accZ',
'gyrX',
'gyrY',
'gyrZ',
263 'magX',
'magY',
'magZ']
264 self_test_results = []
265 for i, name
in enumerate(bit_names):
266 self_test_results.append((name, (data >> i) & 1))
267 return self_test_results
270 """Get the current baudrate id of the device.""" 276 """Set the baudrate of the device using the baudrate id.""" 281 """Get the current error mode of the device.""" 284 error_mode, = struct.unpack(
'!H', data)
288 """Set the error mode of the device. 290 The error mode defines the way the device deals with errors (expect 292 0x0000: ignore any errors except message handling errors, 293 0x0001: in case of missing sampling instance: increase sample 294 counter and do not send error message, 295 0x0002: in case of missing sampling instance: increase sample 296 counter and send error message, 297 0x0003: in case of non-message handling error, an error message is 298 sent and the device will go into Config State. 301 data = struct.pack(
'!H', error_mode)
305 """Get the option flags (MTi-1 series).""" 307 data = self.
write_ack(MID.SetOptionFlags)
308 flags, = struct.unpack(
'!I', data)
312 """Set the option flags (MTi-1 series).""" 314 data = struct.pack(
'!II', set_flags, clear_flags)
318 """Get the location ID of the device.""" 321 location_id, = struct.unpack(
'!H', data)
325 """Set the location ID of the device (arbitrary).""" 327 data = struct.pack(
'!H', location_id)
331 """Restore MT device configuration to factory defaults (soft version). 337 """Get the transmission delay (only RS485).""" 339 data = self.
write_ack(MID.SetTransmitDelay)
340 transmit_delay, = struct.unpack(
'!H', data)
341 return transmit_delay
344 """Set the transmission delay (only RS485).""" 346 data = struct.pack(
'!H', transmit_delay)
347 self.
write_ack(MID.SetTransmitDelay, data)
350 """Get the synchronisation settings.""" 352 data = self.
write_ack(MID.SetSyncSettings)
353 sync_settings = [struct.unpack(
'!BBBBHHHH', data[o:o+12])
354 for o
in range(0, len(data), 12)]
358 """Set the synchronisation settings (mark IV)""" 360 data = b
''.join(struct.pack(
'!BBBBHHHH', *sync_setting)
361 for sync_setting
in sync_settings)
362 self.
write_ack(MID.SetSyncSettings, data)
365 """Ask for the current configuration of the MT device.""" 367 config = self.
write_ack(MID.ReqConfiguration)
369 masterID, period, skipfactor, _, _, _, date, time, num, deviceID,\
370 length, mode, settings =\
371 struct.unpack(
'!IHHHHI8s8s32x32xHIHHI8x', config)
373 raise MTException(
"could not parse configuration.")
378 self.
header = b
'\xFA\xFF\x32' + struct.pack(
'!B', self.
length)
380 self.
header = b
'\xFA\xFF\x32\xFF' + struct.pack(
'!H', self.
length)
381 conf = {
'output-mode': mode,
382 'output-settings': settings,
385 'skipfactor': skipfactor,
386 'Master device ID': masterID,
389 'number of devices': num,
390 'device ID': deviceID}
394 """Get the output configuration of the device (mark IV).""" 396 data = self.
write_ack(MID.SetOutputConfiguration)
397 output_configuration = [struct.unpack(
'!HH', data[o:o+4])
398 for o
in range(0, len(data), 4)]
399 return output_configuration
402 """Set the output configuration of the device (mark IV).""" 404 data = b
''.join(struct.pack(
'!HH', *output)
405 for output
in output_configuration)
406 self.
write_ack(MID.SetOutputConfiguration, data)
409 """Get the NMEA data output configuration.""" 411 data = self.
write_ack(MID.SetStringOutputType)
412 string_output_type, = struct.unpack(
'!H', data)
413 return string_output_type
416 """Set the configuration of the NMEA data output.""" 418 data = struct.pack(
'!H', string_output_type)
419 self.
write_ack(MID.SetStringOutputType, data)
422 """Get the sampling period.""" 425 period, = struct.unpack(
'!H', data)
429 """Set the sampling period.""" 431 data = struct.pack(
'!H', period)
435 """Get the object alignment. 437 parameter indicates the desired alignment quaternion: 438 0 for sensor alignment (RotSensor), 439 1 for local alignment (RotLocal). 442 data = struct.pack(
'!B', parameter)
443 data = self.
write_ack(MID.SetAlignmentRotation, data)
445 q0, q1, q2, q3 = struct.unpack(
'!ffff', data)
446 return parameter, (q0, q1, q2, q3)
447 elif len(data) == 17:
448 param, q0, q1, q2, q3 = struct.unpack(
'!Bffff', data)
449 return param, (q0, q1, q2, q3)
451 raise MTException(
'Could not parse ReqAlignmentRotationAck message:' 452 ' wrong size of message (%d instead of either 16 ' 453 'or 17).' % len(data))
456 """Set the object alignment. 458 parameter indicates the desired alignment quaternion: 459 0 for sensor alignment (RotSensor), 460 1 for local alignment (RotLocal). 463 data = struct.pack(
'!Bffff', parameter, *quaternion)
464 self.
write_ack(MID.SetAlignmentRotation, data)
467 """Get current output mode.""" 470 self.
mode, = struct.unpack(
'!H', data)
474 """Select which information to output.""" 476 data = struct.pack(
'!H', mode)
481 """Get current extended output mode (for alternative UART).""" 483 data = self.
write_ack(MID.SetExtOutputMode)
484 ext_mode, = struct.unpack(
'!H', data)
488 """Set extended output mode (for alternative UART).""" 490 data = struct.pack(
'!H', ext_mode)
491 self.
write_ack(MID.SetExtOutputMode, data)
494 """Get current output mode.""" 496 data = self.
write_ack(MID.SetOutputSettings)
497 self.
settings, = struct.unpack(
'!I', data)
501 """Select how to output the information.""" 503 data = struct.pack(
'!I', settings)
504 self.
write_ack(MID.SetOutputSettings, data)
508 """Set the output skip factor.""" 510 data = struct.pack(
'!H', skipfactor)
511 self.
write_ack(DeprecatedMID.SetOutputSkipFactor, data)
514 """Get data length for mark III devices.""" 517 data = self.
write_ack(DeprecatedMID.ReqDataLength)
518 except MTErrorMessage
as e:
520 sys.stderr.write(
"ReqDataLength message is deprecated and not " 521 "recognised by your device.")
524 self.
length, = struct.unpack(
'!H', data)
526 self.
header = b
'\xFA\xFF\x32' + struct.pack(
'!B', self.
length)
528 self.
header = b
'\xFA\xFF\x32\xFF' + struct.pack(
'!H', self.
length)
532 """Get the stored position of the device. 533 It is used internally for local magnetic declination and local gravity. 538 lat, lon, alt = struct.unpack(
'!ddd', data)
539 elif len(data) == 12:
540 lat, lon, alt = struct.unpack(
'!fff', data)
542 raise MTException(
'Could not parse ReqLatLonAltAck message: wrong' 544 return (lat, lon, alt)
547 """Set the position of the device. 548 It is used internally for local magnetic declination and local gravity. 551 data = struct.pack(
'!ddd', lat, lon, alt)
555 """Get the available XKF scenarios on the device.""" 557 data = self.
write_ack(MID.ReqAvailableScenarios)
560 for i
in range(len(data)/22):
561 scenario_type, version, label =\
562 struct.unpack(
'!BB20s', data[22*i:22*(i+1)])
563 scenarios.append((scenario_type, version, label.strip()))
567 raise MTException(
"could not parse the available XKF scenarios.")
571 """Get the ID of the currently used XKF scenario.""" 573 data = self.
write_ack(MID.SetCurrentScenario)
578 """Set the XKF scenario to use.""" 580 data = struct.pack(
'!BB', 0, scenario_id)
581 self.
write_ack(MID.SetCurrentScenario, data)
584 GetAvailableFilterProfiles = GetAvailableScenarios
585 GetFilterProfile = GetCurrentScenario
586 SetFilterProfile = SetCurrentScenario
589 """Get the current GNSS navigation filter settings.""" 591 data = self.
write_ack(MID.SetGnssPlatform)
592 platform, = struct.unpack(
'!H', data)
596 """Set the GNSS navigation filter settings.""" 598 data = struct.pack(
'!H', platform)
599 self.
write_ack(MID.SetGnssPlatform, data)
602 """Reset the orientation. 604 Code can take several values: 605 0x0000: store current settings (only in config mode), 606 0x0001: heading reset (NOT supported by MTi-G), 607 0x0003: object reset. 609 data = struct.pack(
'!H', code)
610 self.
write_ack(MID.ResetOrientation, data)
613 """Initiate the "no rotation" procedure to estimate gyro biases.""" 615 data = struct.pack(
'!H', duration)
619 """Get UTC time from device.""" 622 ns, year, month, day, hour, minute, second, flag = \
623 struct.unpack(
'!IHBBBBBB', data)
624 return (ns, year, month, day, hour, minute, second, flag)
626 def SetUTCTime(self, ns, year, month, day, hour, minute, second, flag):
627 """Set UTC time on the device.""" 629 data = struct.pack(
'!IHBBBBBB', ns, year, month, day, hour, minute,
634 """Adjust UTC Time of device using correction ticks (0.1 ms).""" 636 data = struct.pack(
'!i', ticks)
637 self.write(MID.AdjustUTCTime, data)
640 """Command of In-run Compass Calibration (ICC).""" 641 if command
not in (0, 1, 2, 3):
642 raise MTException(
"unknown ICC command 0x%02X" % command)
643 cmd_data = struct.pack(
'!B', command)
644 res_data = self.
write_ack(MID.IccCommand, cmd_data)
645 cmd_ack = struct.unpack(
'!B', res_data[:1])
646 payload = res_data[1:]
647 if cmd_ack != command:
648 raise MTException(
"expected ack of command 0x%02X; got 0x%02X " 649 "instead" % (command, cmd_ack))
653 ddt_value, dimension, status = struct.unpack(
'!fBB', payload)
654 return ddt_value, dimension, status
658 state = struct.unpack(
'!B', payload)
665 """Configure the mode and settings of the MT device in legacy mode.""" 669 except MTErrorMessage
as e:
675 except MTException
as e:
677 print "no ack received while switching from MTData2 to MTData." 681 if period
is not None:
683 if skipfactor
is not None:
688 """Read configuration from device in legacy mode.""" 697 if mid == MID.MTData:
699 elif mid == MID.MTData2:
702 raise MTException(
"unknown data message: mid=0x%02X (%s)." %
707 def parse_temperature(data_id, content, ffmt):
709 if (data_id & 0x00F0) == 0x10:
710 o[
'Temp'], = struct.unpack(
'!'+ffmt, content)
712 raise MTException(
"unknown packet: 0x%04X." % data_id)
715 def parse_timestamp(data_id, content, ffmt):
717 if (data_id & 0x00F0) == 0x10:
718 o[
'ns'], o[
'Year'], o[
'Month'], o[
'Day'], o[
'Hour'],\
719 o[
'Minute'], o[
'Second'], o[
'Flags'] =\
720 struct.unpack(
'!LHBBBBBB', content)
721 elif (data_id & 0x00F0) == 0x20:
722 o[
'PacketCounter'], = struct.unpack(
'!H', content)
723 elif (data_id & 0x00F0) == 0x30:
724 o[
'TimeOfWeek'], = struct.unpack(
'!L', content)
725 elif (data_id & 0x00F0) == 0x40:
726 o[
'gpsAge'], = struct.unpack(
'!B', content)
727 elif (data_id & 0x00F0) == 0x50:
728 o[
'pressureAge'], = struct.unpack(
'!B', content)
729 elif (data_id & 0x00F0) == 0x60:
730 o[
'SampleTimeFine'], = struct.unpack(
'!L', content)
731 elif (data_id & 0x00F0) == 0x70:
732 o[
'SampleTimeCoarse'], = struct.unpack(
'!L', content)
733 elif (data_id & 0x00F0) == 0x80:
734 o[
'startFrame'], o[
'endFrame'] = struct.unpack(
'!HH', content)
736 raise MTException(
"unknown packet: 0x%04X." % data_id)
739 def parse_orientation_data(data_id, content, ffmt):
741 if (data_id & 0x000C) == 0x00:
743 elif (data_id & 0x000C) == 0x04:
745 elif (data_id & 0x000C) == 0x08:
747 if (data_id & 0x00F0) == 0x10:
748 o[
'Q0'], o[
'Q1'], o[
'Q2'], o[
'Q3'] = struct.unpack(
'!'+4*ffmt,
750 elif (data_id & 0x00F0) == 0x20:
751 o[
'a'], o[
'b'], o[
'c'], o[
'd'], o[
'e'], o[
'f'], o[
'g'],\
752 o[
'h'], o[
'i'] = struct.unpack(
'!'+9*ffmt, content)
753 elif (data_id & 0x00F0) == 0x30:
754 o[
'Roll'], o[
'Pitch'], o[
'Yaw'] = struct.unpack(
'!'+3*ffmt,
757 raise MTException(
"unknown packet: 0x%04X." % data_id)
760 def parse_pressure(data_id, content, ffmt):
762 if (data_id & 0x00F0) == 0x10:
763 o[
'Pressure'], = struct.unpack(
'!L', content)
765 raise MTException(
"unknown packet: 0x%04X." % data_id)
768 def parse_acceleration(data_id, content, ffmt):
770 if (data_id & 0x000C) == 0x00:
772 elif (data_id & 0x000C) == 0x04:
774 elif (data_id & 0x000C) == 0x08:
776 if (data_id & 0x00F0) == 0x10:
777 o[
'Delta v.x'], o[
'Delta v.y'], o[
'Delta v.z'] = \
778 struct.unpack(
'!'+3*ffmt, content)
779 elif (data_id & 0x00F0) == 0x20:
780 o[
'accX'], o[
'accY'], o[
'accZ'] = \
781 struct.unpack(
'!'+3*ffmt, content)
782 elif (data_id & 0x00F0) == 0x30:
783 o[
'freeAccX'], o[
'freeAccY'], o[
'freeAccZ'] = \
784 struct.unpack(
'!'+3*ffmt, content)
785 elif (data_id & 0x00F0) == 0x40:
786 o[
'accX'], o[
'accY'], o[
'accZ'] = \
787 struct.unpack(
'!'+3*ffmt, content)
789 raise MTException(
"unknown packet: 0x%04X." % data_id)
792 def parse_position(data_id, content, ffmt):
794 if (data_id & 0x000C) == 0x00:
796 elif (data_id & 0x000C) == 0x04:
798 elif (data_id & 0x000C) == 0x08:
800 if (data_id & 0x00F0) == 0x10:
801 o[
'altMsl'], = struct.unpack(
'!'+ffmt, content)
802 elif (data_id & 0x00F0) == 0x20:
803 o[
'altEllipsoid'], = struct.unpack(
'!'+ffmt, content)
804 elif (data_id & 0x00F0) == 0x30:
805 o[
'ecefX'], o[
'ecefY'], o[
'ecefZ'] = \
806 struct.unpack(
'!'+3*ffmt, content)
807 elif (data_id & 0x00F0) == 0x40:
808 o[
'lat'], o[
'lon'] = struct.unpack(
'!'+2*ffmt, content)
810 raise MTException(
"unknown packet: 0x%04X." % data_id)
813 def parse_GNSS(data_id, content, ffmt):
815 if (data_id & 0x00F0) == 0x10:
816 o[
'itow'], o[
'year'], o[
'month'], o[
'day'], o[
'hour'],\
817 o[
'min'], o[
'sec'], o[
'valid'], o[
'tAcc'], o[
'nano'],\
818 o[
'fixtype'], o[
'flags'], o[
'numSV'], o[
'lon'], o[
'lat'],\
819 o[
'height'], o[
'hMSL'], o[
'hAcc'], o[
'vAcc'], o[
'velN'],\
820 o[
'velE'], o[
'velD'], o[
'gSpeed'], o[
'headMot'],\
821 o[
'sAcc'], o[
'headAcc'], o[
'headVeh'], o[
'gdop'],\
822 o[
'pdop'], o[
'tdop'], o[
'vdop'], o[
'hdop'], o[
'ndop'],\
824 struct.unpack(
'!IHBBBBBBIiBBBxiiiiIIiiiiiIIiHHHHHHH',
838 elif (data_id & 0x00F0) == 0x20:
839 o[
'iTOW'], o[
'numSvs'] = struct.unpack(
'!LBxxx', content[:8])
842 for i
in range(o[
'numSvs']):
843 ch[
'gnssId'], ch[
'svId'], ch[
'cno'], ch[
'flags'] = \
844 struct.unpack(
'!BBBB', content[8+4*i:12+4*i])
848 raise MTException(
"unknown packet: 0x%04X." % data_id)
851 def parse_angular_velocity(data_id, content, ffmt):
853 if (data_id & 0x000C) == 0x00:
855 elif (data_id & 0x000C) == 0x04:
857 elif (data_id & 0x000C) == 0x08:
859 if (data_id & 0x00F0) == 0x20:
860 o[
'gyrX'], o[
'gyrY'], o[
'gyrZ'] = \
861 struct.unpack(
'!'+3*ffmt, content)
862 elif (data_id & 0x00F0) == 0x30:
863 o[
'Delta q0'], o[
'Delta q1'], o[
'Delta q2'], o[
'Delta q3'] = \
864 struct.unpack(
'!'+4*ffmt, content)
865 elif (data_id & 0x00F0) == 0x40:
866 o[
'gyrX'], o[
'gyrY'], o[
'gyrZ'] = \
867 struct.unpack(
'!'+3*ffmt, content)
869 raise MTException(
"unknown packet: 0x%04X." % data_id)
872 def parse_GPS(data_id, content, ffmt):
874 if (data_id & 0x00F0) == 0x30:
875 o[
'iTOW'], g, p, t, v, h, n, e = \
876 struct.unpack(
'!LHHHHHHH', content)
877 o[
'gDOP'], o[
'pDOP'], o[
'tDOP'], o[
'vDOP'], o[
'hDOP'], \
878 o[
'nDOP'], o[
'eDOP'] = 0.01*g, 0.01*p, 0.01*t, \
879 0.01*v, 0.01*h, 0.01*n, 0.01*e
880 elif (data_id & 0x00F0) == 0x40:
881 o[
'iTOW'], o[
'fTOW'], o[
'Week'], o[
'gpsFix'], o[
'Flags'], \
882 o[
'ecefX'], o[
'ecefY'], o[
'ecefZ'], o[
'pAcc'], \
883 o[
'ecefVX'], o[
'ecefVY'], o[
'ecefVZ'], o[
'sAcc'], \
884 o[
'pDOP'], o[
'numSV'] = \
885 struct.unpack(
'!LlhBBlllLlllLHxBx', content)
888 elif (data_id & 0x00F0) == 0x80:
889 o[
'iTOW'], o[
'tAcc'], o[
'nano'], o[
'year'], o[
'month'], \
890 o[
'day'], o[
'hour'], o[
'min'], o[
'sec'], o[
'valid'] = \
891 struct.unpack(
'!LLlHBBBBBB', content)
892 elif (data_id & 0x00F0) == 0xA0:
893 o[
'iTOW'], o[
'numCh'] = struct.unpack(
'!LBxxx', content[:8])
896 for i
in range(o[
'numCh']):
897 ch[
'chn'], ch[
'svid'], ch[
'flags'], ch[
'quality'], \
898 ch[
'cno'], ch[
'elev'], ch[
'azim'], ch[
'prRes'] = \
899 struct.unpack(
'!BBBBBbhl', content[8+12*i:20+12*i])
901 o[
'channels'] = channels
903 raise MTException(
"unknown packet: 0x%04X." % data_id)
906 def parse_SCR(data_id, content, ffmt):
908 if (data_id & 0x00F0) == 0x10:
909 o[
'accX'], o[
'accY'], o[
'accZ'], o[
'gyrX'], o[
'gyrY'], \
910 o[
'gyrZ'], o[
'magX'], o[
'magY'], o[
'magZ'], o[
'Temp'] = \
911 struct.unpack(
"!9Hh", content)
912 elif (data_id & 0x00F0) == 0x20:
913 o[
'tempGyrX'], o[
'tempGyrY'], o[
'tempGyrZ'] = \
914 struct.unpack(
"!hhh", content)
916 raise MTException(
"unknown packet: 0x%04X." % data_id)
919 def parse_analog_in(data_id, content, ffmt):
921 if (data_id & 0x00F0) == 0x10:
922 o[
'analogIn1'], = struct.unpack(
"!H", content)
923 elif (data_id & 0x00F0) == 0x20:
924 o[
'analogIn2'], = struct.unpack(
"!H", content)
926 raise MTException(
"unknown packet: 0x%04X." % data_id)
929 def parse_magnetic(data_id, content, ffmt):
931 if (data_id & 0x000C) == 0x00:
933 elif (data_id & 0x000C) == 0x04:
935 elif (data_id & 0x000C) == 0x08:
937 if (data_id & 0x00F0) == 0x20:
938 o[
'magX'], o[
'magY'], o[
'magZ'] = \
939 struct.unpack(
"!3"+ffmt, content)
941 raise MTException(
"unknown packet: 0x%04X." % data_id)
944 def parse_velocity(data_id, content, ffmt):
946 if (data_id & 0x000C) == 0x00:
948 elif (data_id & 0x000C) == 0x04:
950 elif (data_id & 0x000C) == 0x08:
952 if (data_id & 0x00F0) == 0x10:
953 o[
'velX'], o[
'velY'], o[
'velZ'] = \
954 struct.unpack(
"!3"+ffmt, content)
956 raise MTException(
"unknown packet: 0x%04X." % data_id)
959 def parse_status(data_id, content, ffmt):
961 if (data_id & 0x00F0) == 0x10:
962 o[
'StatusByte'], = struct.unpack(
"!B", content)
963 elif (data_id & 0x00F0) == 0x20:
964 o[
'StatusWord'], = struct.unpack(
"!L", content)
965 elif (data_id & 0x00F0) == 0x40:
966 o[
'RSSI'], = struct.unpack(
"!b", content)
968 raise MTException(
"unknown packet: 0x%04X." % data_id)
975 data_id, size = struct.unpack(
'!HB', data[:3])
976 if (data_id & 0x0003) == 0x3:
978 elif (data_id & 0x0003) == 0x0:
981 raise MTException(
"fixed point precision not supported.")
982 content = data[3:3+size]
984 group = data_id & 0xF800
986 if group == XDIGroup.Temperature:
987 output.setdefault(
'Temperature', {}).update(
988 parse_temperature(data_id, content, ffmt))
989 elif group == XDIGroup.Timestamp:
990 output.setdefault(
'Timestamp', {}).update(
991 parse_timestamp(data_id, content, ffmt))
992 elif group == XDIGroup.OrientationData:
993 output.setdefault(
'Orientation Data', {}).update(
994 parse_orientation_data(data_id, content, ffmt))
995 elif group == XDIGroup.Pressure:
996 output.setdefault(
'Pressure', {}).update(
997 parse_pressure(data_id, content, ffmt))
998 elif group == XDIGroup.Acceleration:
999 output.setdefault(
'Acceleration', {}).update(
1000 parse_acceleration(data_id, content, ffmt))
1001 elif group == XDIGroup.Position:
1002 output.setdefault(
'Position', {}).update(
1003 parse_position(data_id, content, ffmt))
1004 elif group == XDIGroup.GNSS:
1005 output.setdefault(
'GNSS', {}).update(
1006 parse_GNSS(data_id, content, ffmt))
1007 elif group == XDIGroup.AngularVelocity:
1008 output.setdefault(
'Angular Velocity', {}).update(
1009 parse_angular_velocity(data_id, content, ffmt))
1010 elif group == XDIGroup.GPS:
1011 output.setdefault(
'GPS', {}).update(
1012 parse_GPS(data_id, content, ffmt))
1013 elif group == XDIGroup.SensorComponentReadout:
1014 output.setdefault(
'SCR', {}).update(
1015 parse_SCR(data_id, content, ffmt))
1016 elif group == XDIGroup.AnalogIn:
1017 output.setdefault(
'Analog In', {}).update(
1018 parse_analog_in(data_id, content, ffmt))
1019 elif group == XDIGroup.Magnetic:
1020 output.setdefault(
'Magnetic', {}).update(
1021 parse_magnetic(data_id, content, ffmt))
1022 elif group == XDIGroup.Velocity:
1023 output.setdefault(
'Velocity', {}).update(
1024 parse_velocity(data_id, content, ffmt))
1025 elif group == XDIGroup.Status:
1026 output.setdefault(
'Status', {}).update(
1027 parse_status(data_id, content, ffmt))
1029 raise MTException(
"unknown XDI group: 0x%04X." % group)
1030 except struct.error:
1031 raise MTException(
"couldn't parse MTData2 message (data_id: " 1032 "0x%04X, size: %d)." % (data_id, size))
1036 """Read and parse a legacy measurement packet.""" 1040 if settings
is None:
1046 if mode & OutputMode.RAW:
1048 o[
'accX'], o[
'accY'], o[
'accZ'], o[
'gyrX'], o[
'gyrY'], \
1049 o[
'gyrZ'], o[
'magX'], o[
'magY'], o[
'magZ'], o[
'temp'] =\
1050 struct.unpack(
'!10H', data[:20])
1054 if mode & OutputMode.RAWGPS:
1056 o[
'Press'], o[
'bPrs'], o[
'ITOW'], o[
'LAT'], o[
'LON'],\
1057 o[
'ALT'], o[
'VEL_N'], o[
'VEL_E'], o[
'VEL_D'], o[
'Hacc'],\
1058 o[
'Vacc'], o[
'Sacc'], o[
'bGPS'] =\
1059 struct.unpack(
'!HBI6i3IB', data[:44])
1061 output[
'RAWGPS'] = o
1063 if mode & OutputMode.Temp:
1064 temp, = struct.unpack(
'!f', data[:4])
1066 output[
'Temp'] = temp
1068 if mode & OutputMode.Calib:
1070 if (settings & OutputSettings.Coordinates_NED):
1074 if not (settings & OutputSettings.CalibMode_GyrMag):
1075 o[
'accX'], o[
'accY'], o[
'accZ'] = struct.unpack(
'!3f',
1078 if not (settings & OutputSettings.CalibMode_AccMag):
1079 o[
'gyrX'], o[
'gyrY'], o[
'gyrZ'] = struct.unpack(
'!3f',
1082 if not (settings & OutputSettings.CalibMode_AccGyr):
1083 o[
'magX'], o[
'magY'], o[
'magZ'] = struct.unpack(
'!3f',
1088 if mode & OutputMode.Orient:
1090 if (settings & OutputSettings.Coordinates_NED):
1094 if settings & OutputSettings.OrientMode_Euler:
1095 o[
'roll'], o[
'pitch'], o[
'yaw'] = struct.unpack(
'!3f',
1098 elif settings & OutputSettings.OrientMode_Matrix:
1099 a, b, c, d, e, f, g, h, i = struct.unpack(
'!9f',
1102 o[
'matrix'] = ((a, b, c), (d, e, f), (g, h, i))
1104 q0, q1, q2, q3 = struct.unpack(
'!4f', data[:16])
1106 o[
'quaternion'] = (q0, q1, q2, q3)
1107 output[
'Orient'] = o
1109 if mode & OutputMode.Auxiliary:
1111 if not (settings & OutputSettings.AuxiliaryMode_NoAIN1):
1112 o[
'Ain_1'], = struct.unpack(
'!H', data[:2])
1114 if not (settings & OutputSettings.AuxiliaryMode_NoAIN2):
1115 o[
'Ain_2'], = struct.unpack(
'!H', data[:2])
1117 output[
'Auxiliary'] = o
1119 if mode & OutputMode.Position:
1121 o[
'Lat'], o[
'Lon'], o[
'Alt'] = struct.unpack(
'!3f', data[:12])
1125 if mode & OutputMode.Velocity:
1127 if (settings & OutputSettings.Coordinates_NED):
1131 o[
'Vel_X'], o[
'Vel_Y'], o[
'Vel_Z'] = struct.unpack(
'!3f',
1136 if mode & OutputMode.Status:
1137 status, = struct.unpack(
'!B', data[:1])
1139 output[
'Stat'] = status
1141 if settings & OutputSettings.Timestamp_SampleCnt:
1142 TS, = struct.unpack(
'!H', data[:2])
1144 output[
'Sample'] = TS
1146 if settings & OutputSettings.Timestamp_UTCTime:
1148 o[
'ns'], o[
'Year'], o[
'Month'], o[
'Day'], o[
'Hour'],\
1149 o[
'Minute'], o[
'Second'], o[
'Flags'] = struct.unpack(
1150 '!ihbbbbb', data[:12])
1152 output[
'Timestamp'] = o
1154 except struct.error, e:
1155 raise MTException(
"could not parse MTData message.")
1157 raise MTException(
"could not parse MTData message (too long).")
1161 """Change the baudrate, reset the device and reopen communication.""" 1162 brid = Baudrates.get_BRID(baudrate)
1166 self.device.baudrate = baudrate
1178 for port
in glob.glob(
"/dev/tty*S*"):
1180 print "Trying '%s'" % port
1184 mtdev_list.append((port, br))
1194 baudrates = (115200, 460800, 921600, 230400, 57600, 38400, 19200, 9600)
1195 for br
in baudrates:
1197 print "Trying %d bd:" % br,
1200 mt =
MTDevice(port, br, timeout=timeout, verbose=verbose,
1201 initial_wait=initial_wait)
1202 except serial.SerialException:
1204 print "fail: unable to open device." 1208 mt.GoToMeasurement()
1221 print """MT device driver. 1223 ./mtdevice.py [commands] [opts] 1227 Print this help and quit. 1229 Reset device to factory defaults. 1230 -a, --change-baudrate=NEW_BAUD 1231 Change baudrate from BAUD (see below) to NEW_BAUD. 1232 -c, --configure=OUTPUT 1233 Configure the device (see OUTPUT description below). 1235 Print MTData. It is the default if no other command is supplied. 1237 Print current MT device configuration. 1238 -x, --xkf-scenario=ID 1239 Change the current XKF scenario. 1240 -l, --legacy-configure 1241 Configure the device in legacy mode (needs MODE and SETTINGS arguments 1245 -y, --synchronization=settings (see below) 1246 Configure the synchronization settings of each sync line (see below). 1247 -u, --utc-time=time (see below) 1248 Set the UTC time buffer of the device. 1249 -g, --gnss-platform=platform 1250 Change the GNSS navigation filter settings (check the documentation). 1251 -o, --option-flags=flags (see below) 1252 Set the option flags. 1253 -j, --icc-command=command (see below) 1254 Send command to the In-run Compass Calibration. 1258 Serial interface of the device (default: /dev/ttyUSB0). If 'auto', then 1259 all serial ports are tested at all baudrates and the first 1260 suitable device is used. 1262 Baudrate of serial interface (default: 115200). If 0, then all 1263 rates are tried until a suitable one is found. 1264 -t, --timeout=TIMEOUT 1265 Timeout of serial communication in second (default: 0.002). 1266 -w, --initial-wait=WAIT 1267 Initial wait to allow device to be ready in second (default: 0.1). 1269 Configuration option: 1271 The format is a sequence of "<group><type><frequency>?<format>?" 1272 separated by commas. 1273 The frequency and format are optional. 1274 The groups and types can be: 1275 t temperature (max frequency: 1 Hz): 1277 i timestamp (max frequency: 2000 Hz): 1280 ii Integer Time of the Week (ITOW) 1282 ic sample time coarse 1284 o orientation data (max frequency: 400 Hz): 1288 b pressure (max frequency: 50 Hz): 1290 a acceleration (max frequency: 2000 Hz (see documentation)): 1293 af free acceleration 1294 ah acceleration HR (max frequency 1000 Hz) 1295 p position (max frequency: 400 Hz): 1296 pa altitude ellipsoid 1298 pl latitude longitude 1299 n GNSS (max frequency: 4 Hz): 1301 ns GNSS satellites info 1302 w angular velocity (max frequency: 2000 Hz (see documentation)): 1305 wh rate of turn HR (max frequency 1000 Hz) 1306 g GPS (max frequency: 4 Hz): 1311 r Sensor Component Readout (max frequency: 2000 Hz): 1312 rr ACC, GYR, MAG, temperature 1313 rt Gyro temperatures 1314 m Magnetic (max frequency: 100 Hz): 1316 v Velocity (max frequency: 400 Hz): 1318 s Status (max frequency: 2000 Hz): 1321 Frequency is specified in decimal and is assumed to be the maximum 1322 frequency if it is omitted. 1323 Format is a combination of the precision for real valued numbers and 1326 f single precision floating point number (32-bit) (default) 1327 d double precision floating point number (64-bit) 1329 e East-North-Up (default) 1333 The default configuration for the MTi-1/10/100 IMUs can be 1334 specified either as: 1337 "wd2000fe,ad2000fe,mf100fe,ip2000,if2000,sw2000" 1338 For getting quaternion orientation in float with sample time: 1340 For longitude, latitude, altitude and orientation (on MTi-G-700): 1341 "pl400fe,pa400fe,oq400fe" 1343 Synchronization settings: 1344 The format follows the xsens protocol documentation. All fields are 1345 required and separated by commas. 1346 Note: The entire synchronization buffer is wiped every time a new one 1347 is set, so it is necessary to specify the settings of multiple 1349 It also possible to clear the synchronization with the argument "clear" 1351 Function (see manual for details): 1352 3 Trigger indication 1353 4 Interval Transition Measurement 1355 9 ClockBiasEstimation 1357 Line (manual for details): 1359 1 GPSClockIn (only available for 700/710) 1360 2 Input Line (SyncIn) 1362 5 ExtTimepulseIn (only available for 700/710) 1363 6 Software (only available for SendLatest with ReqData message) 1365 1 Positive pulse/ Rising edge 1366 2 Negative pulse/ Falling edge 1371 Skip First (unsigned_int): 1372 Number of initial events to skip before taking actions 1373 Skip Factor (unsigned_int): 1374 Number of events to skip before taking action again 1375 Ignored with ReqData. 1376 Pulse Width (unsigned_int): 1378 For SyncOut, the width of the generated pulse in 100 microseconds 1379 unit. Ignored for Toggle pulses. 1381 Delay after receiving a sync pulse to taking action, 1382 100 microseconds units, range [0...600000] 1384 Reference clock period in milliseconds for ClockBiasEstimation 1386 Offset from event to pulse generation. 1387 100 microseconds unit, range [-30000...+30000] 1390 For changing the sync setting of the SyncIn line to trigger indication 1391 with rising edge, one time triggering and no skipping and delay. Enter 1395 Note a number is still in the place for pulse width despite it being 1398 To set multiple lines at once: 1399 ./mtdevice.py -y 3,2,1,0,0,0,0,0 -y 9,0,1,0,0,0,10,0 1401 To clear the synchronization settings of MTi 1402 ./mtdevice.py -y clear 1405 There are two ways to set the UTCtime for the MTi. 1406 Option #1: set MTi to the current UTC time based on local system time with 1408 Option #2: set MTi to a specified UTC time 1409 The time fields are set as follows: 1410 year: range [1999,2099] 1412 day: day of the month, range [1,31] 1413 hour: hour of the day, range [0,23] 1414 min: minute of the hour, range [0,59] 1415 sec: second of the minute, range [0,59] 1416 ns: nanosecond of the second, range [0,1000000000] 1418 1: Valid Time of Week 1419 2: Valid Week Number 1421 Note: the flag is ignored for --utc-time as it is set by the device 1422 itself when connected to a GPS 1425 Set UTC time for the device: 1426 ./mtdevice.py -u now 1427 ./mtdevice.py -u 1999,1,1,0,0,0,0,0 1429 GNSS platform settings: 1430 Only for MTi-G-700/710 with firmware>=1.7. 1431 The following two platform settings are listed in the documentation: 1434 Check the XSens documentation before changing anything. 1437 Several flags can be set or cleared. 1438 0x00000001 DisableAutoStore: when set, configuration changes are not saved 1439 in non-volatile memory (only MTi-1 series) 1440 0x00000002 DisableAutoMeasurement: when set, device will stay in Config 1441 Mode upon start up (only MTi-1 series) 1442 0x00000004 EnableBeidou: when set, enable Beidou and disable GLONASS (only 1444 0x00000010 EnableAHS: enable Active Heading Stabilization (overrides 1446 0x00000080 EnableInRunCompassCalibration: doc is unclear 1447 The flags provided must be a pair of ored values: the first for flags to be 1448 set the second for the flags to be cleared. 1450 Only set DisableAutoStore and DisableAutoMeasurement flags: 1451 ./mtdevice.py -o 0x03,0x00 1452 Disable AHS (clear EnableAHS flag): 1453 ./mtdevice.py -o 0x00,0x10 1454 Set DisableAutoStore and clear DisableAutoMeasurement: 1455 ./mtdevice.py -o 0x02,0x01 1457 In-run Compass Calibration commands: 1458 The idea of ICC is to record magnetic field data during so-called 1459 representative motion in order to better calibrate the magnetometer and 1461 Typical usage would be to issue the start command, then move the device 1462 for some time then issue the stop command. If parameters are acceptable, 1463 these can be stored using the store command. 1465 00: Start representative motion 1466 01: Stop representative motion; return ddt, dimension, and status. 1467 02: Store ICC parameters 1468 03: Get representative motion state; return 1 if active 1469 Check the documentation for more details. 1472 -m, --output-mode=MODE 1473 Legacy mode of the device to select the information to output. 1474 This is required for 'legacy-configure' command. 1475 MODE can be either the mode value in hexadecimal, decimal or 1476 binary form, or a string composed of the following characters 1478 t temperature, [0x0001] 1479 c calibrated data, [0x0002] 1480 o orientation data, [0x0004] 1481 a auxiliary data, [0x0008] 1482 p position data (requires MTi-G), [0x0010] 1483 v velocity data (requires MTi-G), [0x0020] 1484 s status data, [0x0800] 1485 g raw GPS mode (requires MTi-G), [0x1000] 1486 r raw (incompatible with others except raw GPS), [0x4000] 1487 For example, use "--output-mode=so" to have status and 1489 -s, --output-settings=SETTINGS 1490 Legacy settings of the device. This is required for 'legacy-configure' 1492 SETTINGS can be either the settings value in hexadecimal, 1493 decimal or binary form, or a string composed of the following 1494 characters (in any order): 1495 t sample count (excludes 'n') 1496 n no sample count (excludes 't') 1498 q orientation in quaternion (excludes 'e' and 'm') 1499 e orientation in Euler angles (excludes 'm' and 'q') 1500 m orientation in matrix (excludes 'q' and 'e') 1501 A acceleration in calibrated data 1502 G rate of turn in calibrated data 1503 M magnetic field in calibrated data 1504 i only analog input 1 (excludes 'j') 1505 j only analog input 2 (excludes 'i') 1506 N North-East-Down instead of default: X North Z up 1507 For example, use "--output-settings=tqMAG" for all calibrated 1508 data, sample counter and orientation in quaternion. 1510 Sampling period in (1/115200) seconds (default: 1152). 1511 Minimum is 225 (1.95 ms, 512 Hz), maximum is 1152 1513 Note that for legacy devices it is the period at which sampling occurs, 1514 not the period at which messages are sent (see below). 1517 -f, --deprecated-skip-factor=SKIPFACTOR 1518 Only for mark III devices. 1519 Number of samples to skip before sending MTData message 1521 The frequency at which MTData message is send is: 1522 115200/(PERIOD * (SKIPFACTOR + 1)) 1523 If the value is 0xffff, no data is send unless a ReqData request 1533 shopts =
'hra:c:eild:b:m:s:p:f:x:vy:u:g:o:j:t:w:' 1534 lopts = [
'help',
'reset',
'change-baudrate=',
'configure=',
'echo',
1535 'inspect',
'legacy-configure',
'device=',
'baudrate=',
1536 'output-mode=',
'output-settings=',
'period=',
1537 'deprecated-skip-factor=',
'xkf-scenario=',
'verbose',
1538 'synchronization=',
'utc-time=',
'gnss-platform=',
1539 'option-flags=',
'icc-command=',
'timeout=',
'initial-wait=']
1541 opts, args = getopt.gnu_getopt(sys.argv[1:], shopts, lopts)
1542 except getopt.GetoptError, e:
1547 device =
'/dev/ttyUSB0' 1563 if o
in (
'-h',
'--help'):
1566 elif o
in (
'-r',
'--reset'):
1567 actions.append(
'reset')
1568 elif o
in (
'-a',
'--change-baudrate'):
1570 new_baudrate = int(a)
1572 print "change-baudrate argument must be integer." 1574 actions.append(
'change-baudrate')
1575 elif o
in (
'-c',
'--configure'):
1577 if output_config
is None:
1579 actions.append(
'configure')
1580 elif o
in (
'-e',
'--echo'):
1581 actions.append(
'echo')
1582 elif o
in (
'-i',
'--inspect'):
1583 actions.append(
'inspect')
1584 elif o
in (
'-l',
'--legacy-configure'):
1585 actions.append(
'legacy-configure')
1586 elif o
in (
'-x',
'--xkf-scenario'):
1590 print "xkf-scenario argument must be integer." 1592 actions.append(
'xkf-scenario')
1593 elif o
in (
'-y',
'--synchronization'):
1595 if new_sync_settings
is None:
1597 sync_settings.append(new_sync_settings)
1598 actions.append(
'synchronization')
1599 elif o
in (
'-u',
'--setUTCtime'):
1601 if UTCtime_settings
is None:
1603 actions.append(
'setUTCtime')
1604 elif o
in (
'-d',
'--device'):
1606 elif o
in (
'-b',
'--baudrate'):
1610 print "baudrate argument must be integer." 1612 elif o
in (
'-m',
'--output-mode'):
1616 elif o
in (
'-s',
'--output-settings'):
1618 if settings
is None:
1620 elif o
in (
'-p',
'--period'):
1624 print "period argument must be integer." 1626 elif o
in (
'-f',
'--deprecated-skip-factor'):
1630 print "skip-factor argument must be integer." 1632 elif o
in (
'-v',
'--verbose'):
1634 elif o
in (
'-g',
'--gnss-platform'):
1636 if platform
is None:
1638 actions.append(
'gnss-platform')
1639 elif o
in (
'-o',
'--option-flags'):
1641 if flag_tuple
is None:
1643 actions.append(
'option-flags')
1644 elif o
in (
'-j',
'--icc-command'):
1646 if icc_command
is None:
1648 actions.append(
'icc-command')
1649 elif o
in (
'-t',
'--timeout'):
1653 print "timeout argument must be a floating number." 1655 elif o
in (
'-w',
'--initial-wait'):
1657 initial_wait = float(a)
1659 print "initial-wait argument must be a floating number." 1663 if len(actions) == 0:
1664 actions.append(
'echo')
1666 if device ==
'auto':
1668 initial_wait=initial_wait)
1670 print "Detected devices:",
"".join(
'\n\t%s @ %d' % (d, p)
1672 print "Using %s @ %d" % devs[0]
1673 device, baudrate = devs[0]
1675 print "No suitable device found." 1679 baudrate =
find_baudrate(device, timeout=timeout, verbose=verbose,
1680 initial_wait=initial_wait)
1682 print "No suitable baudrate found." 1686 mt =
MTDevice(device, baudrate, timeout=timeout, verbose=verbose,
1687 initial_wait=initial_wait)
1688 except serial.SerialException:
1691 if 'inspect' in actions:
1693 if 'change-baudrate' in actions:
1694 print "Changing baudrate from %d to %d:" % (baudrate,
1697 mt.ChangeBaudrate(new_baudrate)
1699 if 'reset' in actions:
1700 print "Restoring factory defaults",
1702 mt.RestoreFactoryDefaults()
1704 if 'configure' in actions:
1705 print "Changing output configuration",
1707 mt.SetOutputConfiguration(output_config)
1709 if 'synchronization' in actions:
1710 print "Changing synchronization settings",
1712 mt.SetSyncSettings(sync_settings)
1714 if 'setUTCtime' in actions:
1715 print "Setting UTC time in the device",
1717 mt.SetUTCTime(UTCtime_settings[6],
1718 UTCtime_settings[0],
1719 UTCtime_settings[1],
1720 UTCtime_settings[2],
1721 UTCtime_settings[3],
1722 UTCtime_settings[4],
1723 UTCtime_settings[5],
1724 UTCtime_settings[7])
1726 if 'gnss-platform' in actions:
1727 print "Setting GNSS platform",
1729 mt.SetGnssPlatform(platform)
1731 if 'option-flags' in actions:
1732 print "Setting option flags",
1734 mt.SetOptionFlags(*flag_tuple)
1736 if 'icc-command' in actions:
1737 icc_command_names = {
1738 0:
'start representative motion',
1739 1:
'stop representative motion',
1740 2:
'store ICC results',
1741 3:
'representative motion state'}
1742 print "Sending ICC command 0x%02X (%s):" % (
1743 icc_command, icc_command_names[icc_command]),
1745 res = mt.IccCommand(icc_command)
1746 if icc_command == 0x00:
1748 elif icc_command == 0x01:
1750 elif icc_command == 0x02:
1752 elif icc_command == 0x03:
1753 res_string = {0:
'representative motion inactive',
1754 1:
'representation motion active'}
1755 print "0x02X (%s)" % (res, res_string.get(res,
'unknown'))
1756 if 'legacy-configure' in actions:
1758 print "output-mode is require to configure the device in "\
1761 if settings
is None:
1762 print "output-settings is required to configure the device "\
1765 print "Configuring in legacy mode",
1767 mt.configure_legacy(mode, settings, period, skipfactor)
1769 if 'xkf-scenario' in actions:
1770 print "Changing XKF scenario",
1772 mt.SetCurrentScenario(new_xkf)
1774 if 'echo' in actions:
1780 print mt.read_measurement(mode, settings)
1781 except KeyboardInterrupt:
1783 except MTErrorMessage
as e:
1784 print "MTErrorMessage:", e
1785 except MTException
as e:
1786 print "MTException:", e
1791 def config_fmt(config):
1792 """Hexadecimal configuration.""" 1793 return '[%s]' %
', '.join(
'(0x%04X, %d)' % (mode, freq)
1794 for (mode, freq)
in config)
1796 def hex_fmt(size=4):
1797 """Factory for hexadecimal representation formatter.""" 1798 fmt =
'0x%%0%dX' % (2*size)
1801 """Hexadecimal representation.""" 1806 def sync_fmt(settings):
1807 """Synchronization settings: N*12 bytes""" 1808 return '[%s]' %
', '.join(
'(0x%02X, 0x%02X, 0x%02X, 0x%02X,' 1809 ' 0x%04X, 0x%04X, 0x%04X, 0x%04X)' % s
1812 def try_message(m, f, formater=None, *args, **kwargs):
1815 if formater
is not None:
1816 print formater(f(*args, **kwargs))
1818 pprint.pprint(f(*args, **kwargs), indent=4)
1819 except MTTimeoutException
as e:
1820 print 'timeout: might be unsupported by your device.' 1821 except MTErrorMessage
as e:
1823 print 'message unsupported by your device.' 1826 print "Device: %s at %d Bd:" % (device, baudrate)
1827 try_message(
"device ID:", mt.GetDeviceID, hex_fmt(4))
1828 try_message(
"product code:", mt.GetProductCode)
1829 try_message(
"hardware version:", mt.GetHardwareVersion)
1830 try_message(
"firmware revision:", mt.GetFirmwareRev)
1831 try_message(
"baudrate:", mt.GetBaudrate)
1832 try_message(
"error mode:", mt.GetErrorMode, hex_fmt(2))
1833 try_message(
"option flags:", mt.GetOptionFlags, hex_fmt(4))
1834 try_message(
"location ID:", mt.GetLocationID, hex_fmt(2))
1835 try_message(
"transmit delay:", mt.GetTransmitDelay)
1836 try_message(
"synchronization settings:", mt.GetSyncSettings, sync_fmt)
1837 try_message(
"general configuration:", mt.GetConfiguration)
1838 try_message(
"output configuration (mark IV devices):",
1839 mt.GetOutputConfiguration, config_fmt)
1840 try_message(
"string output type:", mt.GetStringOutputType)
1841 try_message(
"period:", mt.GetPeriod)
1842 try_message(
"alignment rotation sensor:", mt.GetAlignmentRotation,
1844 try_message(
"alignment rotation local:", mt.GetAlignmentRotation,
1846 try_message(
"output mode:", mt.GetOutputMode, hex_fmt(2))
1847 try_message(
"extended output mode:", mt.GetExtOutputMode, hex_fmt(2))
1848 try_message(
"output settings:", mt.GetOutputSettings, hex_fmt(4))
1849 try_message(
"GPS coordinates (lat, lon, alt):", mt.GetLatLonAlt)
1850 try_message(
"GNSS platform:", mt.GetGnssPlatform)
1851 try_message(
"available scenarios:", mt.GetAvailableScenarios)
1852 try_message(
"current scenario ID:", mt.GetCurrentScenario)
1853 try_message(
"UTC time:", mt.GetUTCTime)
1857 """Parse the mark IV output configuration argument.""" 1861 'iu': (0x1010, 2000),
1862 'ip': (0x1020, 2000),
1863 'ii': (0x1030, 2000),
1864 'if': (0x1060, 2000),
1865 'ic': (0x1070, 2000),
1866 'ir': (0x1080, 2000),
1867 'oq': (0x2010, 400),
1868 'om': (0x2020, 400),
1869 'oe': (0x2030, 400),
1871 'ad': (0x4010, 2000),
1872 'aa': (0x4020, 2000),
1873 'af': (0x4030, 2000),
1874 'ah': (0x4040, 1000),
1875 'pa': (0x5020, 400),
1876 'pp': (0x5030, 400),
1877 'pl': (0x5040, 400),
1880 'wr': (0x8020, 2000),
1881 'wd': (0x8030, 2000),
1882 'wh': (0x8040, 1000),
1887 'rr': (0xA010, 2000),
1888 'rt': (0xA020, 2000),
1889 'mf': (0xC020, 100),
1890 'vv': (0xD010, 400),
1891 'sb': (0xE010, 2000),
1892 'sw': (0xE020, 2000)
1895 format_dict = {
'f': 0x00,
'd': 0x03,
'e': 0x00,
'n': 0x04,
'w': 0x08}
1896 config_re = re.compile(
'([a-z]{2})(\d+)?([fdenw])?([fdnew])?')
1897 output_configuration = []
1899 for item
in config_arg.split(
','):
1900 group, frequency, fmt1, fmt2 = config_re.findall(item.lower())[0]
1901 code, max_freq = code_dict[group]
1902 if fmt1
in format_dict:
1903 code |= format_dict[fmt1]
1904 if fmt2
in format_dict:
1905 code |= format_dict[fmt2]
1907 frequency = min(max_freq, int(frequency))
1909 frequency = max_freq
1910 output_configuration.append((code, frequency))
1911 return output_configuration
1912 except (IndexError, KeyError):
1913 print 'could not parse output specification "%s"' % item
1918 """Parse command line output-mode argument.""" 1939 mode |= OutputMode.Temp
1941 mode |= OutputMode.Calib
1943 mode |= OutputMode.Orient
1945 mode |= OutputMode.Auxiliary
1947 mode |= OutputMode.Position
1949 mode |= OutputMode.Velocity
1951 mode |= OutputMode.Status
1953 mode |= OutputMode.RAWGPS
1955 mode |= OutputMode.RAW 1957 print "Unknown output-mode specifier: '%s'" % c
1963 """Parse command line output-settings argument.""" 1971 settings = int(arg, 2)
1976 settings = int(arg, 16)
1983 calib_mode = OutputSettings.CalibMode_Mask
1987 timestamp = OutputSettings.Timestamp_SampleCnt
1989 timestamp = OutputSettings.Timestamp_None
1991 timestamp |= OutputSettings.Timestamp_UTCTime 1993 orient_mode = OutputSettings.OrientMode_Quaternion
1995 orient_mode = OutputSettings.OrientMode_Euler
1997 orient_mode = OutputSettings.OrientMode_Matrix
1999 calib_mode &= OutputSettings.CalibMode_Acc
2001 calib_mode &= OutputSettings.CalibMode_Gyr
2003 calib_mode &= OutputSettings.CalibMode_Mag
2005 calib_mode &= OutputSettings.AuxiliaryMode_NoAIN2
2007 calib_mode &= OutputSettings.AuxiliaryMode_NoAIN1
2009 NED = OutputSettings.Coordinates_NED
2011 print "Unknown output-settings specifier: '%s'" % c
2013 settings = timestamp | orient_mode | calib_mode | NED
2018 """Parse command line synchronization-settings argument.""" 2020 sync_settings = [0, 0, 0, 0, 0, 0, 0, 0]
2021 return sync_settings
2024 sync_settings = arg.split(
',')
2027 sync_settings = tuple([int(i)
for i
in sync_settings])
2029 print "Synchronization sync_settings must be integers." 2032 if sync_settings[0]
in (3, 4, 8, 9, 11)
and \
2033 sync_settings[1]
in (0, 1, 2, 4, 5, 6)
and \
2034 sync_settings[2]
in (1, 2, 3)
and \
2035 sync_settings[3]
in (0, 1):
2036 return sync_settings
2038 print "Invalid synchronization settings." 2043 """Parse command line UTC time specification.""" 2047 timestamp = datetime.datetime.utcnow()
2049 time_settings.append(timestamp.year)
2050 time_settings.append(timestamp.month)
2051 time_settings.append(timestamp.day)
2052 time_settings.append(timestamp.hour)
2053 time_settings.append(timestamp.minute)
2054 time_settings.append(timestamp.second)
2055 time_settings.append(timestamp.microsecond*1000)
2056 time_settings.append(0)
2057 return time_settings
2060 time_settings = arg.split(
',')
2062 time_settings = [int(i)
for i
in time_settings]
2064 print "UTCtime settings must be integers." 2068 if 1999 <= time_settings[0] <= 2099
and\
2069 1 <= time_settings[1] <= 12
and\
2070 1 <= time_settings[2] <= 31
and\
2071 0 <= time_settings[3] <= 23
and\
2072 0 <= time_settings[4] <= 59
and\
2073 0 <= time_settings[5] <= 59
and\
2074 0 <= time_settings[6] <= 1000000000:
2075 return time_settings
2077 print "Invalid UTCtime settings." 2082 """Parse and check command line GNSS platform argument.""" 2086 print "GNSS platform must be an integer." 2088 if platform
in (0, 8):
2091 print "Invalid GNSS platform argument (excepted 0 or 8)." 2096 """Parse and check command line option flags argument.""" 2098 set_flag, clear_flag = map(
lambda s: int(s.strip(), base=0),
2100 return (set_flag, clear_flag)
2102 print 'incorrect option flags specification (expected a pair of '\
2108 """Parse and check ICC command argument.""" 2110 icc_command = int(arg, base=0)
2111 if icc_command
not in range(4):
2115 print 'invalid ICC command "%s"; expected 0, 1, 2, or 3.' % arg
2119 if __name__ ==
'__main__':
def SetPeriod(self, period)
def waitfor(self, size=1)
def get_gnss_platform(arg)
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 SetGnssPlatform(self, platform)
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 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 GetHardwareVersion(self)
def SetOptionFlags(self, set_flags, clear_flags)
def SetTransmitDelay(self, transmit_delay)
def write_ack(self, mid, data=b'', n_resend=30, n_read=25)
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 IccCommand(self, command)
def GoToMeasurement(self)
def GetGnssPlatform(self)
def get_option_flags(arg)
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)