Show EOL distros: 

imu_tools: imu_complementary_filter | imu_filter_madgwick | rviz_imu_plugin

Package Summary

Filter which fuses angular velocities, accelerations, and (optionally) magnetic readings from a generic IMU device into a quaternion to represent the orientation of the device wrt the global frame. Based on the algorithm by Roberto G. Valenti etal. described in the paper "Keeping a Good Attitude: A Quaternion-Based Orientation Filter for IMUs and MARGs" available at http://www.mdpi.com/1424-8220/15/8/19302 .

imu_tools: imu_complementary_filter | imu_filter_madgwick | rviz_imu_plugin

Package Summary

Filter which fuses angular velocities, accelerations, and (optionally) magnetic readings from a generic IMU device into a quaternion to represent the orientation of the device wrt the global frame. Based on the algorithm by Roberto G. Valenti etal. described in the paper "Keeping a Good Attitude: A Quaternion-Based Orientation Filter for IMUs and MARGs" available at http://www.mdpi.com/1424-8220/15/8/19302 .

imu_tools: imu_complementary_filter | imu_filter_madgwick | rviz_imu_plugin

Package Summary

Filter which fuses angular velocities, accelerations, and (optionally) magnetic readings from a generic IMU device into a quaternion to represent the orientation of the device wrt the global frame. Based on the algorithm by Roberto G. Valenti etal. described in the paper "Keeping a Good Attitude: A Quaternion-Based Orientation Filter for IMUs and MARGs" available at http://www.mdpi.com/1424-8220/15/8/19302 .

imu_tools: imu_complementary_filter | imu_filter_madgwick | rviz_imu_plugin

Package Summary

Filter which fuses angular velocities, accelerations, and (optionally) magnetic readings from a generic IMU device into a quaternion to represent the orientation of the device wrt the global frame. Based on the algorithm by Roberto G. Valenti etal. described in the paper "Keeping a Good Attitude: A Quaternion-Based Orientation Filter for IMUs and MARGs" available at http://www.mdpi.com/1424-8220/15/8/19302 .

imu_tools: imu_complementary_filter | imu_filter_madgwick | rviz_imu_plugin

Package Summary

Filter which fuses angular velocities, accelerations, and (optionally) magnetic readings from a generic IMU device into a quaternion to represent the orientation of the device wrt the global frame. Based on the algorithm by Roberto G. Valenti etal. described in the paper "Keeping a Good Attitude: A Quaternion-Based Orientation Filter for IMUs and MARGs" available at http://www.mdpi.com/1424-8220/15/8/19302 .

imu_tools: imu_complementary_filter | imu_filter_madgwick | rviz_imu_plugin

Package Summary

Filter which fuses angular velocities, accelerations, and (optionally) magnetic readings from a generic IMU device into a quaternion to represent the orientation of the device wrt the global frame. Based on the algorithm by Roberto G. Valenti etal. described in the paper "Keeping a Good Attitude: A Quaternion-Based Orientation Filter for IMUs and MARGs" available at http://www.mdpi.com/1424-8220/15/8/19302 .

Details

Supported devices

The filter should be general enough to use with any IMU which publishes angular velocities and linear accelerations (and optionally magnetic filed).

It has been tested with:

Phidgets Spatial 3/3/3

Xsense MTx

Example

Here's an example of the filter in operation:

ROS API

complementary_filter_node

Subscribed Topics

imu/data_raw (sensor_msgs/Imu)
  • Message containing raw IMU data, including angular velocities and linear accelerations.
imu/mag (sensor_msgs/MagneticField)
  • [optional] Magnetic field vector

Published Topics

imu/data (sensor_msgs/Imu)
  • The fused Imu message, containing the orientation.
imu/rpy/filtered (geometry_msgs/Vector3)
  • Debug only: The roll, pitch and yaw angles corresponding to the orientation published on the imu_data topic. (only published when ~publish_debug_topics == true)
imu/steady_state (std_msgs/Bool)
  • Debug only: Whether we are in the steady state when doing bias estimation. (only published when ~publish_debug_topics == true)

Parameters

Not Dynamically Reconfigurable Parameters
~gain_acc (double, default: 0.01)
  • Gain for the complementary filter, belongs in [0, 1].
~gain_mag (double, default: 0.01)
  • Gain for the complementary filter, belongs in [0, 1].
~bias_alpha (double, default: 0.01)
  • Bias estimation gain, belongs in [0, 1].
~do_bias_estimation (bool, default: true)
  • Whether to do bias estimation of the angular velocity (gyroscope readings) or not.
~do_adaptive_gain (bool, default: true)
  • Whether to do adaptive gain or not.
~use_mag (bool, default: false)
  • Whether to use the magnetic field data in the data fusion.
~fixed_frame (string, default: odom)
  • The parent frame to be used in publish_tf.
~publish_tf (bool, default: false)
  • Whether to publish a TF transform that represents the orientation of the IMU, using the frame specified in fixed_frame as the parent frame and the frame given in the input imu message as the child frame.
~reverse_tf (bool, default: false)
  • If set to true, publish transforms from imu_frame to fixed frame instead of the other way around.
~constant_dt (double, default: 0.0)
  • The dt to use; if 0.0 (default), compute dt dynamically from message headers.
~publish_debug_topics (bool, default: false)
  • If set to true, publish a couple of debug topics.

Provided tf Transforms

fixed_frameimu_frame
  • Only for debug purposes! This is a transform from the fixed frame (specified in the parameter fixed_frame, default: "odom") to the header.frame_id frame from the incoming imu messages. Only the rotation is valid.

Bug Reports & Feature Requests

We appreciate the time and effort spent submitting bug reports and feature requests.

Use GitHub to report bugs or submit feature requests. [View active issues]

Wiki: imu_complementary_filter (last edited 2022-04-11 10:52:46 by MartinGuenther)