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...).
The ROS node is a wrapper around the mtdevice::MTDevice class. It can publish the following topics, depending on the configuration of the device:
/imu/data
(sensor_msgs::Imu): orientation, angular velocity, linear acceleration,/fix
(sensor_msgs::NavSatFix): longitude, latitude, altitude (from GPS only for MTi-G),/fix_extended
(gps_common::GPSFix): more complete GPS information than /fix
,/velocity
(geometry_msgs::TwistStamped): linear and angular velocity,/magnetic
(geometry_msgs::Vector3Stamped): direction of magnetic field,/temperature
(std_msgs::Float32): temperature.It also publishes diagnostics information.
If the IMU is set to raw mode, the values in of the /imu/data
, /velocity
and /magnetic
topics are the 16 bits output of the AD converters.
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.
The nodes can take the following parameters:
auto
): the path of the device file to connect to the imu; auto
will look through all serial devices to find the first one.auto
device); 0 will try to auto-detect baudrate./base_imu
): the frame id of the IMU.It might be necessary to add the user to the dialout
group so that the node can communicate with the device.