xsens_driver Documentation

xsens_driver

ROS Driver for XSens MT/MTi/MTi-G devices.

The xsens_driver package provides mtnode.py, a generic ROS node publishing the data streamed by an XSens motion tracker (MT, MTi, MTi-G...) from third, fourth or fifth generation.

Topics

The ROS node is a wrapper around the mtdevice::MTDevice class. It can publish the following topics, depending on the configuration of the device:

It can also publish diagnostics information.

Finally, it always publishes the decoded message as a std_msgs::String representing the Python dictionary on /imu_data_str.

If the IMU is set to raw mode, the values of the /imu/data, /velocity and /magnetic topics are the 16 bits output of the AD converters and therefore not in usual units.

The covariance information in the sensor_msgs::Imu message are filled with default values from the MTx/MTi/MTi-G documentation but may not be exact; it also does not correspond to the covariance of the internal XKF.

Parameters

The nodes can take the following parameters:

Permissions

It might be necessary to add the user to the dialout group so that the node can communicate with the device.

Configuration using mtdevice.py

mtdevice.py can be used on the command line to configure or inspect the current configuration of the device, see usage below.

1 MT device driver.
2 Usage:
3  ./mtdevice.py [commands] [opts]
4 
5 Commands:
6  -h, --help
7  Print this help and quit.
8  -r, --reset
9  Reset device to factory defaults.
10  -a, --change-baudrate=NEW_BAUD
11  Change baudrate from BAUD (see below) to NEW_BAUD.
12  -c, --configure=OUTPUT
13  Configure the device (see OUTPUT description below).
14  -e, --echo
15  Print MTData. It is the default if no other command is supplied.
16  -i, --inspect
17  Print current MT device configuration.
18  -x, --xkf-scenario=ID
19  Change the current XKF scenario.
20  -l, --legacy-configure
21  Configure the device in legacy mode (needs MODE and SETTINGS arguments
22  below).
23  -v, --verbose
24  Verbose output.
25  -y, --synchronization=settings (see below)
26  Configure the synchronization settings of each sync line (see below).
27  -u, --utc-time=time (see below)
28  Set the UTC time buffer of the device.
29  -g, --gnss-platform=platform
30  Change the GNSS navigation filter settings (check the documentation).
31  -o, --option-flags=flags (see below)
32  Set the option flags.
33  -j, --icc-command=command (see below)
34  Send command to the In-run Compass Calibration.
35 
36 Generic options:
37  -d, --device=DEV
38  Serial interface of the device (default: /dev/ttyUSB0). If 'auto', then
39  all serial ports are tested at all baudrates and the first
40  suitable device is used.
41  -b, --baudrate=BAUD
42  Baudrate of serial interface (default: 115200). If 0, then all
43  rates are tried until a suitable one is found.
44  -t, --timeout=TIMEOUT
45  Timeout of serial communication in second (default: 0.002).
46  -w, --initial-wait=WAIT
47  Initial wait to allow device to be ready in second (default: 0.1).
48 
49 Configuration option:
50  OUTPUT
51  The format is a sequence of "<group><type><frequency>?<format>?"
52  separated by commas.
53  The frequency and format are optional.
54  The groups and types can be:
55  t temperature (max frequency: 1 Hz):
56  tt temperature
57  i timestamp (max frequency: 2000 Hz):
58  iu UTC time
59  ip packet counter
60  ii Integer Time of the Week (ITOW)
61  if sample time fine
62  ic sample time coarse
63  ir frame range
64  o orientation data (max frequency: 400 Hz):
65  oq quaternion
66  om rotation matrix
67  oe Euler angles
68  b pressure (max frequency: 50 Hz):
69  bp baro pressure
70  a acceleration (max frequency: 2000 Hz (see documentation)):
71  ad delta v
72  aa acceleration
73  af free acceleration
74  ah acceleration HR (max frequency 1000 Hz)
75  p position (max frequency: 400 Hz):
76  pa altitude ellipsoid
77  pp position ECEF
78  pl latitude longitude
79  n GNSS (max frequency: 4 Hz):
80  np GNSS PVT data
81  ns GNSS satellites info
82  w angular velocity (max frequency: 2000 Hz (see documentation)):
83  wr rate of turn
84  wd delta q
85  wh rate of turn HR (max frequency 1000 Hz)
86  g GPS (max frequency: 4 Hz):
87  gd DOP
88  gs SOL
89  gu time UTC
90  gi SV info
91  r Sensor Component Readout (max frequency: 2000 Hz):
92  rr ACC, GYR, MAG, temperature
93  rt Gyro temperatures
94  m Magnetic (max frequency: 100 Hz):
95  mf magnetic Field
96  v Velocity (max frequency: 400 Hz):
97  vv velocity XYZ
98  s Status (max frequency: 2000 Hz):
99  sb status byte
100  sw status word
101  Frequency is specified in decimal and is assumed to be the maximum
102  frequency if it is omitted.
103  Format is a combination of the precision for real valued numbers and
104  coordinate system:
105  precision:
106  f single precision floating point number (32-bit) (default)
107  d double precision floating point number (64-bit)
108  coordinate system:
109  e East-North-Up (default)
110  n North-East-Down
111  w North-West-Up
112  Examples:
113  The default configuration for the MTi-1/10/100 IMUs can be
114  specified either as:
115  "wd,ad,mf,ip,if,sw"
116  or
117  "wd2000fe,ad2000fe,mf100fe,ip2000,if2000,sw2000"
118  For getting quaternion orientation in float with sample time:
119  "oq400fw,if2000"
120  For longitude, latitude, altitude and orientation (on MTi-G-700):
121  "pl400fe,pa400fe,oq400fe"
122 
123 Synchronization settings:
124  The format follows the xsens protocol documentation. All fields are
125  required and separated by commas.
126  Note: The entire synchronization buffer is wiped every time a new one
127  is set, so it is necessary to specify the settings of multiple
128  lines at once.
129  It also possible to clear the synchronization with the argument "clear"
130 
131  Function (see manual for details):
132  3 Trigger indication
133  4 Interval Transition Measurement
134  8 SendLatest
135  9 ClockBiasEstimation
136  11 StartSampling
137  Line (manual for details):
138  0 ClockIn
139  1 GPSClockIn (only available for 700/710)
140  2 Input Line (SyncIn)
141  4 SyncOut
142  5 ExtTimepulseIn (only available for 700/710)
143  6 Software (only available for SendLatest with ReqData message)
144  Polarity:
145  1 Positive pulse/ Rising edge
146  2 Negative pulse/ Falling edge
147  3 Both/ Toggle
148  Trigger Type:
149  0 multiple times
150  1 once
151  Skip First (unsigned_int):
152  Number of initial events to skip before taking actions
153  Skip Factor (unsigned_int):
154  Number of events to skip before taking action again
155  Ignored with ReqData.
156  Pulse Width (unsigned_int):
157  Ignored for SyncIn.
158  For SyncOut, the width of the generated pulse in 100 microseconds
159  unit. Ignored for Toggle pulses.
160  Delay:
161  Delay after receiving a sync pulse to taking action,
162  100 microseconds units, range [0...600000]
163  Clock Period:
164  Reference clock period in milliseconds for ClockBiasEstimation
165  Offset:
166  Offset from event to pulse generation.
167  100 microseconds unit, range [-30000...+30000]
168 
169  Examples:
170  For changing the sync setting of the SyncIn line to trigger indication
171  with rising edge, one time triggering and no skipping and delay. Enter
172  the settings as:
173  "3,2,1,1,0,0,0,0"
174 
175  Note a number is still in the place for pulse width despite it being
176  ignored.
177 
178  To set multiple lines at once:
179  ./mtdevice.py -y 3,2,1,0,0,0,0,0 -y 9,0,1,0,0,0,10,0
180 
181  To clear the synchronization settings of MTi
182  ./mtdevice.py -y clear
183 
184 UTC time settings:
185  There are two ways to set the UTCtime for the MTi.
186  Option #1: set MTi to the current UTC time based on local system time with
187  the option 'now'
188  Option #2: set MTi to a specified UTC time
189  The time fields are set as follows:
190  year: range [1999,2099]
191  month: range [1,12]
192  day: day of the month, range [1,31]
193  hour: hour of the day, range [0,23]
194  min: minute of the hour, range [0,59]
195  sec: second of the minute, range [0,59]
196  ns: nanosecond of the second, range [0,1000000000]
197  flag:
198  1: Valid Time of Week
199  2: Valid Week Number
200  4: valid UTC
201  Note: the flag is ignored for --utc-time as it is set by the device
202  itself when connected to a GPS
203 
204  Examples:
205  Set UTC time for the device:
206  ./mtdevice.py -u now
207  ./mtdevice.py -u 1999,1,1,0,0,0,0,0
208 
209 GNSS platform settings:
210  Only for MTi-G-700/710 with firmware>=1.7.
211  The following two platform settings are listed in the documentation:
212  0: Portable
213  8: Airbone <4g
214  Check the XSens documentation before changing anything.
215 
216 Option flags:
217  Several flags can be set or cleared.
218  0x00000001 DisableAutoStore: when set, configuration changes are not saved
219  in non-volatile memory (only MTi-1 series)
220  0x00000002 DisableAutoMeasurement: when set, device will stay in Config
221  Mode upon start up (only MTi-1 series)
222  0x00000004 EnableBeidou: when set, enable Beidou and disable GLONASS (only
223  MTi-G-710)
224  0x00000010 EnableAHS: enable Active Heading Stabilization (overrides
225  magnetic reference)
226  0x00000080 EnableInRunCompassCalibration: doc is unclear
227  The flags provided must be a pair of ored values: the first for flags to be
228  set the second for the flags to be cleared.
229  Examples:
230  Only set DisableAutoStore and DisableAutoMeasurement flags:
231  ./mtdevice.py -o 0x03,0x00
232  Disable AHS (clear EnableAHS flag):
233  ./mtdevice.py -o 0x00,0x10
234  Set DisableAutoStore and clear DisableAutoMeasurement:
235  ./mtdevice.py -o 0x02,0x01
236 
237 In-run Compass Calibration commands:
238  The idea of ICC is to record magnetic field data during so-called
239  representative motion in order to better calibrate the magnetometer and
240  improve the fusion.
241  Typical usage would be to issue the start command, then move the device
242  for some time then issue the stop command. If parameters are acceptable,
243  these can be stored using the store command.
244  Commands:
245  00: Start representative motion
246  01: Stop representative motion; return ddt, dimension, and status.
247  02: Store ICC parameters
248  03: Get representative motion state; return 1 if active
249  Check the documentation for more details.
250 
251 Legacy options:
252  -m, --output-mode=MODE
253  Legacy mode of the device to select the information to output.
254  This is required for 'legacy-configure' command.
255  MODE can be either the mode value in hexadecimal, decimal or
256  binary form, or a string composed of the following characters
257  (in any order):
258  t temperature, [0x0001]
259  c calibrated data, [0x0002]
260  o orientation data, [0x0004]
261  a auxiliary data, [0x0008]
262  p position data (requires MTi-G), [0x0010]
263  v velocity data (requires MTi-G), [0x0020]
264  s status data, [0x0800]
265  g raw GPS mode (requires MTi-G), [0x1000]
266  r raw (incompatible with others except raw GPS), [0x4000]
267  For example, use "--output-mode=so" to have status and
268  orientation data.
269  -s, --output-settings=SETTINGS
270  Legacy settings of the device. This is required for 'legacy-configure'
271  command.
272  SETTINGS can be either the settings value in hexadecimal,
273  decimal or binary form, or a string composed of the following
274  characters (in any order):
275  t sample count (excludes 'n')
276  n no sample count (excludes 't')
277  u UTC time
278  q orientation in quaternion (excludes 'e' and 'm')
279  e orientation in Euler angles (excludes 'm' and 'q')
280  m orientation in matrix (excludes 'q' and 'e')
281  A acceleration in calibrated data
282  G rate of turn in calibrated data
283  M magnetic field in calibrated data
284  i only analog input 1 (excludes 'j')
285  j only analog input 2 (excludes 'i')
286  N North-East-Down instead of default: X North Z up
287  For example, use "--output-settings=tqMAG" for all calibrated
288  data, sample counter and orientation in quaternion.
289  -p, --period=PERIOD
290  Sampling period in (1/115200) seconds (default: 1152).
291  Minimum is 225 (1.95 ms, 512 Hz), maximum is 1152
292  (10.0 ms, 100 Hz).
293  Note that for legacy devices it is the period at which sampling occurs,
294  not the period at which messages are sent (see below).
295 
296 Deprecated options:
297  -f, --deprecated-skip-factor=SKIPFACTOR
298  Only for mark III devices.
299  Number of samples to skip before sending MTData message
300  (default: 0).
301  The frequency at which MTData message is send is:
302  115200/(PERIOD * (SKIPFACTOR + 1))
303  If the value is 0xffff, no data is send unless a ReqData request
304  is made.


xsens_driver
Author(s):
autogenerated on Mon Sep 9 2019 03:44:33