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 imu (MT, MTi, MTi-G...).

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, --setUTCTime=time (see below)
28  Sets the UTC time buffer of the device
29 
30 Generic options:
31  -d, --device=DEV
32  Serial interface of the device (default: /dev/ttyUSB0). If 'auto', then
33  all serial ports are tested at all baudrates and the first
34  suitable device is used.
35  -b, --baudrate=BAUD
36  Baudrate of serial interface (default: 115200). If 0, then all
37  rates are tried until a suitable one is found.
38  -t, --timeout=TIMEOUT
39  Timeout of serial communication in second (default: 0.002).
40  -w, --initial-wait=WAIT
41  Initial wait to allow device to be ready in second (default: 0.1).
42 
43 Configuration option:
44  OUTPUT
45  The format is a sequence of "<group><type><frequency>?<format>?"
46  separated by commas.
47  The frequency and format are optional.
48  The groups and types can be:
49  t temperature (max frequency: 1 Hz):
50  tt temperature
51  i timestamp (max frequency: 2000 Hz):
52  iu UTC time
53  ip packet counter
54  ii Integer Time of the Week (ITOW)
55  if sample time fine
56  ic sample time coarse
57  ir frame range
58  o orientation data (max frequency: 400 Hz):
59  oq quaternion
60  om rotation matrix
61  oe Euler angles
62  b pressure (max frequency: 50 Hz):
63  bp baro pressure
64  a acceleration (max frequency: 2000 Hz (see documentation)):
65  ad delta v
66  aa acceleration
67  af free acceleration
68  ah acceleration HR (max frequency 1000 Hz)
69  p position (max frequency: 400 Hz):
70  pa altitude ellipsoid
71  pp position ECEF
72  pl latitude longitude
73  n GNSS (max frequency: 4 Hz):
74  np GNSS PVT data
75  ns GNSS satellites info
76  w angular velocity (max frequency: 2000 Hz (see documentation)):
77  wr rate of turn
78  wd delta q
79  wh rate of turn HR (max frequency 1000 Hz)
80  g GPS (max frequency: 4 Hz):
81  gd DOP
82  gs SOL
83  gu time UTC
84  gi SV info
85  r Sensor Component Readout (max frequency: 2000 Hz):
86  rr ACC, GYR, MAG, temperature
87  rt Gyro temperatures
88  m Magnetic (max frequency: 100 Hz):
89  mf magnetic Field
90  v Velocity (max frequency: 400 Hz):
91  vv velocity XYZ
92  s Status (max frequency: 2000 Hz):
93  sb status byte
94  sw status word
95  Frequency is specified in decimal and is assumed to be the maximum
96  frequency if it is omitted.
97  Format is a combination of the precision for real valued numbers and
98  coordinate system:
99  precision:
100  f single precision floating point number (32-bit) (default)
101  d double precision floating point number (64-bit)
102  coordinate system:
103  e East-North-Up (default)
104  n North-East-Down
105  w North-West-Up
106  Examples:
107  The default configuration for the MTi-1/10/100 IMUs can be
108  specified either as:
109  "wd,ad,mf,ip,if,sw"
110  or
111  "wd2000fe,ad2000fe,mf100fe,ip2000,if2000,sw2000"
112  For getting quaternion orientation in float with sample time:
113  "oq400fw,if2000"
114  For longitude, latitude, altitude and orientation (on MTi-G-700):
115  "pl400fe,pa400fe,oq400fe"
116 
117 Synchronization settings:
118  The format follows the xsens protocol documentation. All fields are required
119  and separated by commas.
120  Note: The entire synchronization buffer is wiped every time a new one
121  is set, so it is necessary to specify the settings of multiple
122  lines at once.
123  It also possible to clear the synchronization with the argument "clear"
124 
125  Function (see manual for details):
126  3 Trigger indication
127  4 Interval Transition Measurement
128  8 SendLatest
129  9 ClockBiasEstimation
130  11 StartSampling
131  Line (manual for details):
132  0 ClockIn
133  1 GPSClockIn (only available for 700/710)
134  2 Input Line (SyncIn)
135  4 SyncOut
136  5 ExtTimepulseIn (only available for 700/710)
137  6 Software (only available for SendLatest with ReqData message)
138  Polarity:
139  1 Positive pulse/ Rising edge
140  2 Negative pulse/ Falling edge
141  3 Both/ Toggle
142  Trigger Type:
143  0 multiple times
144  1 once
145  Skip First (unsigned_int):
146  Number of initial events to skip before taking actions
147  Skip Factor (unsigned_int):
148  Number of events to skip before taking action again
149  Ignored with ReqData.
150  Pulse Width (unsigned_int):
151  Ignored for SyncIn.
152  For SyncOut, the width of the generated pulse in 100 microseconds
153  unit. Ignored for Toggle pulses.
154  Delay:
155  Delay after receiving a sync pulse to taking action,
156  100 microseconds units, range [0...600000]
157  Clock Period:
158  Reference clock period in milliseconds for ClockBiasEstimation
159  Offset:
160  Offset from event to pulse generation.
161  100 microseconds unit, range [-30000...+30000]
162 
163  Examples:
164  For changing the sync setting of the SyncIn line to trigger indication
165  with rising edge, one time triggering and no skipping and delay. Enter
166  the settings as:
167  "3,2,1,1,0,0,0,0"
168 
169  Note a number is still in the place for pulse width despite it being
170  ignored.
171 
172  To set multiple lines at once:
173  ./mtdevice.py -y 3,2,1,0,0,0,0,0 -y 9,0,1,0,0,0,10,0
174 
175  To clear the synchronization settings of MTi
176  ./mtdevice.py -y clear
177 
178 SetUTCTime settings:
179  There are two ways to set the UTCtime for the MTi.
180  Option #1: set MTi to the current UTC time based on local system time with
181  the option 'now'
182  Option #2: set MTi to a specified UTC time
183  The time fields are set as follows:
184  year: range [1999,2099]
185  month: range [1,12]
186  day: day of the month, range [1,31]
187  hour: hour of the day, range [0,23]
188  min: minute of the hour, range [0,59]
189  sec: second of the minute, range [0,59]
190  ns: nanosecond of the second, range [0,1000000000]
191  flag:
192  1: Valid Time of Week
193  2: Valid Week Number
194  4: valid UTC
195  Note: the flag is ignored for setUTCTime as it is set by the module
196  itself when connected to a GPS
197 
198  Examples:
199  Set UTC time for the device:
200  ./mtdevice.py -u now
201  ./mtdevice.py -u 1999,1,1,0,0,0,0,0
202 
203 Legacy options:
204  -m, --output-mode=MODE
205  Legacy mode of the device to select the information to output.
206  This is required for 'legacy-configure' command.
207  MODE can be either the mode value in hexadecimal, decimal or
208  binary form, or a string composed of the following characters
209  (in any order):
210  t temperature, [0x0001]
211  c calibrated data, [0x0002]
212  o orientation data, [0x0004]
213  a auxiliary data, [0x0008]
214  p position data (requires MTi-G), [0x0010]
215  v velocity data (requires MTi-G), [0x0020]
216  s status data, [0x0800]
217  g raw GPS mode (requires MTi-G), [0x1000]
218  r raw (incompatible with others except raw GPS), [0x4000]
219  For example, use "--output-mode=so" to have status and
220  orientation data.
221  -s, --output-settings=SETTINGS
222  Legacy settings of the device. This is required for 'legacy-configure'
223  command.
224  SETTINGS can be either the settings value in hexadecimal,
225  decimal or binary form, or a string composed of the following
226  characters (in any order):
227  t sample count (excludes 'n')
228  n no sample count (excludes 't')
229  u UTC time
230  q orientation in quaternion (excludes 'e' and 'm')
231  e orientation in Euler angles (excludes 'm' and 'q')
232  m orientation in matrix (excludes 'q' and 'e')
233  A acceleration in calibrated data
234  G rate of turn in calibrated data
235  M magnetic field in calibrated data
236  i only analog input 1 (excludes 'j')
237  j only analog input 2 (excludes 'i')
238  N North-East-Down instead of default: X North Z up
239  For example, use "--output-settings=tqMAG" for all calibrated
240  data, sample counter and orientation in quaternion.
241  -p, --period=PERIOD
242  Sampling period in (1/115200) seconds (default: 1152).
243  Minimum is 225 (1.95 ms, 512 Hz), maximum is 1152
244  (10.0 ms, 100 Hz).
245  Note that for legacy devices it is the period at which sampling occurs,
246  not the period at which messages are sent (see below).
247 
248 Deprecated options:
249  -f, --deprecated-skip-factor=SKIPFACTOR
250  Only for mark III devices.
251  Number of samples to skip before sending MTData message
252  (default: 0).
253  The frequency at which MTData message is send is:
254  115200/(PERIOD * (SKIPFACTOR + 1))
255  If the value is 0xffff, no data is send unless a ReqData request
256  is made.


xsens_driver
Author(s):
autogenerated on Thu Jun 6 2019 19:13:06