Only released in EOL distros:  

lse_imu_drivers: lse_xsens_mti

Package Summary

Xsens MTi node. The existing xsens_mti node is distributed in the form of a library and requires the MTi to be set to a determined configuration to work. We had some old code laying around so we just ported it to ROS. This sends the MTi to configuration mode at start and sets it to the propper mode of operation.

Also check the xsens_mti package.

Supported Hardware

Xsens MTi

Xsens MTi-G

ROS API

mti_node

mti_node is a driver for the Xsens MTi/MTi-G Inertial Measurement Unit. It publishes orientation, angular velocity, linear velocity, linear acceleration, altitude, latitude and longitude (covariances are not yet supported), and complies with the IMU API and Sensor message for NavSat API and odometry API. Take a look at the unsupported C++ API for further features.

Published Topics

imu/data (sensor_msgs/Imu)
  • Streaming inertial data from the IMU.
fix (sensor_msgs/NavSatFix)
  • Streaming GPS data from the IMU.
odom (nav_msgs/Odometry)
  • Streaming odometry data from the IMU (linear velocity, angular velocity, orientation).

Parameters

~baudrate (int, default: 115200)
  • Baudrate of the MTi.
~frame_id (string, default: /base_imu)
  • The frame in which the MTi readings will be returned.
~temperature (bool, default: false)
  • Configure the sensor to get its temperature in degrees Celcius.
~calibrated (bool, default: true)
  • Configure the sensor to get its accelerations, rate of turn and magnetic field in X, Y and Z axes.
~orientation (bool, default: true)
  • Configure the sensor to get its quaternions.
~auxiliary (bool, default: false)
  • Configure the sensor to get its analog input #1 and #2.
~position (bool, default: false)
  • Configure the sensor to get its latitude, longitude and altitude.
~velocity (bool, default: false)
  • Configure the sensor to get its velocity X, Y and Z. Note that velocity in North East Down can be obtained by changing velocityModeNED.
~status (bool, default: false)
  • Configure the sensor to get flags that represent the status and estimated validity of the output.
~rawGPS (bool, default: false)
  • Configure the sensor to get pressure sensor and GPS data (see GPS PVT data in the Xsens documentation).
~rawInertial (bool, default: false)
  • Configure the sensor to get the uncalibrated raw data output of the accelerations, rate of turn and magnetic field in X, Y and Z axes.
~timeStamp (bool, default: false)
  • Configure the sensor to get no timestamp or a sample counter.
~orientationMode (int, default: Quaternion (0))
  • Configure the sensor to get Quaternion(0), Euler angles(1) or Matrix(2).
~enableAcceleration (bool, default: false)
  • Configure the sensor to get acceleration.
~enableRateOfTurn (bool, default: false)
  • Configure the sensor to get rate of turn.
~enableMagnetometer (bool, default: false)
  • Configure the sensor to get magnetometer.
~velocityModeNED (bool, default: false)
  • Configure the sensor to get the velocity in North East Down.
~scenario (int, default: Automotive (2))
  • Configure the sensor to set the scenario to use (see 'XKF Scenarios' sections in the device specific manuals).
~GPSLeverArm_X (double, default: 0)
  • Configure the position of the lever arm.
~GPSLeverArm_Y (double, default: 0)
  • Configure the position of the lever arm.
~GPSLeverArm_Z (double, default: 0)
  • Configure the position of the lever arm.

Wiki: lse_xsens_mti (last edited 2012-06-12 13:36:41 by NicolasVignard)