This project contains a ROS2 driver for the Xsens MTw Awinda system sensors.
- Xsens MTw Awinda System
- The driver is developed upon the XDA 2022, with ROS2 on Ubuntu 22.04 LTS
- XDA 2022 =/= public XDA 2022 (the public XDA 2022 only supports MTi devices)
- No need to download the Xsens MT Software Suite for Linux separately
- ISO C++17 Standard corrections have been applied to the XDA 2022 files
- Instead of using the Xsens Quaternion, this driver uses the state-of-the-art quaternion filter VQF
Tested with Ubuntu 22.04 and ROS2 Humble.
- Data recording (output format as a .csv file with three headers)
- Node control via button presses or ROS2 services
- IMU timeout warning
- Custom configuration using a .yaml file
- Option to disable IMUs when shutting down the node
- Simultaneous orientation visualization of multiple IMUs in RViz
The driver publishes all sensor data to the topic /xsens_imu_data
. If the set ROS2 publish rate is higher than the IMU update rate, the driver will publish the same data until the next update. Custom messages IMUData.msg
, IMUDataArray.msg
and Quaternion.msg
are used. The /config/params.yaml
can be used to easily set the desired parameters. The /config/imu_mapping.yaml
is only used for a specific IMU setup. It will just move the orientations in a more "visually correct" position (experimental). Using xsens_mtw_visualization
without any config, will just publish the TFs of all IMUs next to each other for visibility.
ros2 run xsens_mtw_driver_ros2 xsens_mtw_manager
ros2 run xsens_mtw_driver_ros2 xsens_mtw_visualization
ros2 launch xsens_mtw_driver_ros2 xsens_mtw_manager.launch.py
(loads/config/params.yaml
but no keyboard inputs)ros2 launch xsens_mtw_driver_ros2 xsens_mtw_visualization.launch.py
(loadsconfig/imu_mapping.yaml
) [experimental]
/xsens_mtw_manager/status
/xsens_mtw_manager/get_ready
/xsens_mtw_manager/imu_reset
/xsens_mtw_manager/start_recording
/xsens_mtw_manager/stop_recording
/xsens_mtw_manager/restart
These services are using the std_srvs/srv/trigger.hpp
.
The time in timestamp
is tracked from the start of the node and will be reset to 0
when starting to record by default. This can be disabled in the config/params.yaml
.
Currently the recording will only save the quaternions.
Currently the recorded data is saved in the same directy where the node is started.
IMUs | desiredUpdateRate (max) |
---|---|
1 - 5 | 120 Hz |
6 - 9 | 100 Hz |
10 | 80 Hz |
11 - 20 | 60 Hz |
21 - 32 | 40 Hz |
Starting the xsens_mtw_manager
node through launch files will prevent conio.c
from reading terminal keyboard inputs. Use the custom node services instead or manually add the parameters in the command line when running the node. Example:
ros2 run xsens_mtw_driver_ros2 xsens_mtw_manager --ros-args -p ros2_rate:=200 -p imu_rate:=100
Make sure you are in the correct group:
$ ls -l /dev/ttyUSB0
crw-rw---- 1 root dialout 188, 0 May 4 13:37 /dev/ttyUSB0
$ groups
"username" adm cdrom sudo dip plugdev lpadmin sambashare
Add yourself to the group:
$ sudo usermod -G dialout -a $USER
$ newgrp dialout
More troubleshooting on the xsens_mti_driver page
Make sure to add /opt/ros/<ros2version>/include/**
to the includePath
in your c_cpp_properties.json
from your .vscode
folder.
- Xsens Software & Documentation
- VQF - A Versatile Quaternion-based Filter for IMU Orientation Estimation
- qleonardolp - xsens_mtw_driver-release
- ChangcongWang - xsens_mtw_driver-release [fork] (ROS2 Migration with Xsens SDK 4.6)
- Implement more parameters for
/config/params.yaml