forked from ethz-asl/ethzasl_xsens_driver
-
Notifications
You must be signed in to change notification settings - Fork 1
/
mainpage.dox
311 lines (282 loc) · 14.6 KB
/
mainpage.dox
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
/**
\mainpage
\htmlinclude manifest.html
The \b xsens_driver package provides \b mtnode.py, a generic ROS node publishing the data streamed by an XSens imu (MT, MTi, MTi-G...).
\section topics Topics
The ROS node is a wrapper around the \b mtdevice::MTDevice class. It can publish the following topics, depending on the configuration of the device:
- \c /imu/data (<a href="http://www.ros.org/doc/api/sensor_msgs/html/msg/Imu.html">sensor_msgs::Imu</a>): orientation, angular velocity, linear acceleration,
- \c /fix (<a href="http://www.ros.org/doc/api/sensor_msgs/html/msg/NavSatFix.html">sensor_msgs::NavSatFix</a>): longitude, latitude, altitude (from filtered/fused GPS and IMU),
- \c /raw_fix (<a href="http://www.ros.org/doc/api/sensor_msgs/html/msg/NavSatFix.html">sensor_msgs::NavSatFix</a>): longitude, latitude, altitude (from ONLY GPS),
- \c /fix_extended (<a href="http://www.ros.org/doc/api/gps_common/html/msg/GPSFix.html">gps_common::GPSFix</a>): more complete GPS information than \c /fix,
- \c /velocity (<a href="http://www.ros.org/doc/api/geometry_msgs/html/msg/TwistStamped.html">geometry_msgs::TwistStamped</a>): angular velocity is in body frame, linear velocity is in world frame and fused with GPS measurement.
- \c /magnetic (<a href="http://www.ros.org/doc/api/geometry_msgs/html/msg/Vector3Stamped.html">geometry_msgs::Vector3Stamped</a>): direction of magnetic field,
- \c /temperature (<a href="http://www.ros.org/doc/api/std_msgs/html/msg/Float32.html">std_msgs::Float32</a>): temperature,
- \c /pressure (<a href="http://www.ros.org/doc/api/std_msgs/html/msg/Float32.html">std_msgs::Float32</a>): pressure,
- \c /analog_in1 (<a href="http://www.ros.org/doc/api/std_msgs/html/msg/UInt16.html">std_msgs::UInt16</a>): first analog input,
- \c /analog_in2 (<a href="http://www.ros.org/doc/api/std_msgs/html/msg/UInt16.html">std_msgs::UInt16</a>): second analog input.
It can also publish <a href="http://www.ros.org/wiki/diagnostics">diagnostics</a> information.
Finally, it always publishes the decoded message as a <a href="http://www.ros.org/doc/api/std_msgs/html/msg/String.html">std_msgs::String</a> representing the Python dictionary on \c /imu_data_str.
If the IMU is set to raw mode, the values of the \c /imu/data, \c /velocity and \c /magnetic topics are the 16 bits output of the AD converters and therefore not in usual units.
The covariance information in the <a href="http://www.ros.org/doc/api/sensor_msgs/html/msg/Imu.html">sensor_msgs::Imu</a> 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.
\section params Parameters
The nodes can take the following parameters:
- \a ~device (\c auto): the path of the device file to connect to the imu; \c auto will look through all serial devices to find the first one.
- \a ~baudrate (0): the baudrate of the IMU (unused for \c auto device); 0 will try to auto-detect baudrate.
- \a ~timeout (0.002): the timeout for communication with the IMU.
- \a ~initial_wait (0.1): initial wait to allow the device to come up before trying to communicate.
- \a ~frame_id (\c /base_imu): the frame id of the IMU.
- \a ~frame_local (\c ENU): the desired frame orientation (\c ENU, \c NED, or \c NWU).
- \a ~no_rotation_duration (0): the int duration in seconds of the no-rotation calibration procedure at the start of the node (only for mark iv devices). If 0, the procedure is not launched.
- \a ~angular_velocity_covariance_diagonal ([0.0004, 0.0004, 0.0004]) diagonal elements of the covariance matrix on the angular velocity published on the \c /imu/data topic.
- \a ~linear_acceleration_covariance_diagonal ([0.0004, 0.0004, 0.0004]) diagonal elements of the covariance matrix on the linear acceleration published on the \c /imu/data topic.
- \a ~orientation_covariance_diagonal ([0.01745, 0.01745, 0.15708]) diagonal elements of the covariance matrix on the orientation published on the \c /imu/data topic.
\section dialout Permissions
It might be necessary to add the user to the \c dialout group so that the node can communicate with the device.
\section config Configuration using mtdevice.py
\b mtdevice.py can be used on the command line to configure or inspect the current configuration of the device, see usage below.
\code{.unparsed}
MT device driver.
Usage:
./mtdevice.py [commands] [opts]
Commands:
-h, --help
Print this help and quit.
-r, --reset
Reset device to factory defaults.
-a, --change-baudrate=NEW_BAUD
Change baudrate from BAUD (see below) to NEW_BAUD.
-c, --configure=OUTPUT
Configure the device (see OUTPUT description below).
-e, --echo
Print MTData. It is the default if no other command is supplied.
-i, --inspect
Print current MT device configuration.
-x, --xkf-scenario=ID
Change the current XKF scenario.
-l, --legacy-configure
Configure the device in legacy mode (needs MODE and SETTINGS arguments
below).
-v, --verbose
Verbose output.
-y, --synchronization=settings (see below)
Configure the synchronization settings of each sync line (see below)
-u, --setUTCTime=time (see below)
Sets the UTC time buffer of the device
Generic options:
-d, --device=DEV
Serial interface of the device (default: /dev/ttyUSB0). If 'auto', then
all serial ports are tested at all baudrates and the first
suitable device is used.
-b, --baudrate=BAUD
Baudrate of serial interface (default: 115200). If 0, then all
rates are tried until a suitable one is found.
-t, --timeout=TIMEOUT
Timeout of serial communication in second (default: 0.002).
-w, --initial-wait=WAIT
Initial wait to allow device to be ready in second (default: 0.1).
Configuration option:
OUTPUT
The format is a sequence of "<group><type><frequency>?<format>?"
separated by commas.
The frequency and format are optional.
The groups and types can be:
t temperature (max frequency: 1 Hz):
tt temperature
i timestamp (max frequency: 2000 Hz):
iu UTC time
ip packet counter
ii Integer Time of the Week (ITOW)
if sample time fine
ic sample time coarse
ir frame range
o orientation data (max frequency: 400 Hz):
oq quaternion
om rotation matrix
oe Euler angles
b pressure (max frequency: 50 Hz):
bp baro pressure
a acceleration (max frequency: 2000 Hz (see documentation)):
ad delta v
aa acceleration
af free acceleration
ah acceleration HR (max frequency 1000 Hz)
p position (max frequency: 400 Hz):
pa altitude ellipsoid
pp position ECEF
pl latitude longitude
n GNSS (max frequency: 4 Hz):
np GNSS PVT data
ns GNSS satellites info
w angular velocity (max frequency: 2000 Hz (see documentation)):
wr rate of turn
wd delta q
wh rate of turn HR (max frequency 1000 Hz)
g GPS (max frequency: 4 Hz):
gd DOP
gs SOL
gu time UTC
gi SV info
r Sensor Component Readout (max frequency: 2000 Hz):
rr ACC, GYR, MAG, temperature
rt Gyro temperatures
m Magnetic (max frequency: 100 Hz):
mf magnetic Field
v Velocity (max frequency: 400 Hz):
vv velocity XYZ
s Status (max frequency: 2000 Hz):
sb status byte
sw status word
Frequency is specified in decimal and is assumed to be the maximum
frequency if it is omitted.
Format is a combination of the precision for real valued numbers and
coordinate system:
precision:
f single precision floating point number (32-bit) (default)
d double precision floating point number (64-bit)
coordinate system:
e East-North-Up (default)
n North-East-Down
w North-West-Up
Examples:
The default configuration for the MTi-1/10/100 IMUs can be
specified either as:
"wd,ad,mf,ip,if,sw"
or
"wd2000fe,ad2000fe,mf100fe,ip2000,if2000,sw2000"
For getting quaternion orientation in float with sample time:
"oq400fw,if2000"
For longitude, latitude, altitude and orientation (on MTi-G-700):
"pl400fe,pa400fe,oq400fe"
Synchronization settings:
The format follows the xsens protocol documentation. All fields are required
and separated by commas.
Note: The entire synchronization buffer is wiped every time a new one
is set, so it is necessary to specify the settings of multiple
lines at once.
It also possible to clear the synchronization with the argument "clear"
Function (see manual for details):
3 Trigger indication
4 Interval Transition Measurement
8 SendLatest
9 ClockBiasEstimation
11 StartSampling
Line (manual for details):
0 ClockIn
1 GPSClockIn (only available for 700/710)
2 Input Line (SyncIn)
4 SyncOut
5 ExtTimepulseIn (only available for 700/710)
6 Software (only available for SendLatest with ReqData message)
Polarity:
1 Positive pulse/ Rising edge
2 Negative pulse/ Falling edge
3 Both/ Toggle
Trigger Type:
0 multiple times
1 once
Skip First (unsigned_int):
Number of initial events to skip before taking actions
Skip Factor (unsigned_int):
Number of events to skip before taking action again
Ignored with ReqData.
Pulse Width (unsigned_int):
Ignored for SyncIn.
For SyncOut, the width of the generated pulse in 100 microseconds
unit. Ignored for Toggle pulses.
Delay:
Delay after receiving a sync pulse to taking action,
100 microseconds units, range [0...600000]
Clock Period:
Reference clock period in milliseconds for ClockBiasEstimation
Offset:
Offset from event to pulse generation.
100 microseconds unit, range [-30000...+30000]
Examples:
For changing the sync setting of the SyncIn line to trigger indication
with rising edge, one time triggering and no skipping and delay. Enter
the settings as:
"3,2,1,1,0,0,0,0"
Note a number is still in the place for pulse width despite it being
ignored.
To set multiple lines at once:
./mtdevice.py -y 3,2,1,0,0,0,0,0 -y 9,0,1,0,0,0,10,0
To clear the synchronization settings of MTi
./mtdevice.py -y clear
SetUTCTime settings:
There are two ways to set the UTCtime for the MTi.
Option #1: set MTi to the current UTC time based on local system time with
the option 'now'
Option #2: set MTi to a specified UTC time
The time fields are set as follows:
year: range [1999,2099]
month: range [1,12]
day: day of the month, range [1,31]
hour: hour of the day, range [0,23]
min: minute of the hour, range [0,59]
sec: second of the minute, range [0,59]
ns: nanosecond of the second, range [0,1000000000]
flag:
1: Valid Time of Week
2: Valid Week Number
4: valid UTC
Note: the flag is ignored for setUTCTime as it is set by the module
itself when connected to a GPS
Examples:
Set UTC time for the device:
./mtdevice.py -u now
./mtdevice.py -u 1999,1,1,0,0,0,0,0
Legacy options:
-m, --output-mode=MODE
Legacy mode of the device to select the information to output.
This is required for 'legacy-configure' command.
MODE can be either the mode value in hexadecimal, decimal or
binary form, or a string composed of the following characters
(in any order):
t temperature, [0x0001]
c calibrated data, [0x0002]
o orientation data, [0x0004]
a auxiliary data, [0x0008]
p position data (requires MTi-G), [0x0010]
v velocity data (requires MTi-G), [0x0020]
s status data, [0x0800]
g raw GPS mode (requires MTi-G), [0x1000]
r raw (incompatible with others except raw GPS), [0x4000]
For example, use "--output-mode=so" to have status and
orientation data.
-s, --output-settings=SETTINGS
Legacy settings of the device. This is required for 'legacy-configure'
command.
SETTINGS can be either the settings value in hexadecimal,
decimal or binary form, or a string composed of the following
characters (in any order):
t sample count (excludes 'n')
n no sample count (excludes 't')
u UTC time
q orientation in quaternion (excludes 'e' and 'm')
e orientation in Euler angles (excludes 'm' and 'q')
m orientation in matrix (excludes 'q' and 'e')
A acceleration in calibrated data
G rate of turn in calibrated data
M magnetic field in calibrated data
i only analog input 1 (excludes 'j')
j only analog input 2 (excludes 'i')
N North-East-Down instead of default: X North Z up
For example, use "--output-settings=tqMAG" for all calibrated
data, sample counter and orientation in quaternion.
-p, --period=PERIOD
Sampling period in (1/115200) seconds (default: 1152).
Minimum is 225 (1.95 ms, 512 Hz), maximum is 1152
(10.0 ms, 100 Hz).
Note that for legacy devices it is the period at which sampling occurs,
not the period at which messages are sent (see below).
Deprecated options:
-f, --deprecated-skip-factor=SKIPFACTOR
Only for mark III devices.
Number of samples to skip before sending MTData message
(default: 0).
The frequency at which MTData message is send is:
115200/(PERIOD * (SKIPFACTOR + 1))
If the value is 0xffff, no data is send unless a ReqData request
is made.
\endcode
*/