Show EOL distros:
Package Summary
Filter which fuses angular velocities, accelerations, and (optionally) magnetic readings from a generic IMU device into an orientation. Based on code by Sebastian Madgwick, http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms.
- Author: Ivan Dryanovski
- License: GPL
- Source: git https://github.com/ccny-ros-pkg/imu_tools.git (branch: fuerte)
Package Summary
Filter which fuses angular velocities, accelerations, and (optionally) magnetic readings from a generic IMU device into an orientation. Based on code by Sebastian Madgwick, http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms.
- Maintainer: Ivan Dryanovski <ivan.dryanovski AT gmail DOT com>
- Author: Ivan Dryanovski
- License: GPL
- Source: git https://github.com/ccny-ros-pkg/imu_tools.git (branch: groovy)
Package Summary
Filter which fuses angular velocities, accelerations, and (optionally) magnetic readings from a generic IMU device into an orientation. Based on code by Sebastian Madgwick, http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms.
- Maintainer status: developed
- Maintainer: Martin Günther <martin.guenther1980 AT gmail DOT com>, Ivan Dryanovski <ivan.dryanovski AT gmail DOT com>
- Author: Ivan Dryanovski
- License: GPL
- Source: git https://github.com/ccny-ros-pkg/imu_tools.git (branch: hydro)
Package Summary
Filter which fuses angular velocities, accelerations, and (optionally) magnetic readings from a generic IMU device into an orientation. Based on code by Sebastian Madgwick, http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms.
- Maintainer status: developed
- Maintainer: Martin Günther <martin.guenther1980 AT gmail DOT com>, Ivan Dryanovski <ivan.dryanovski AT gmail DOT com>
- Author: Ivan Dryanovski
- License: GPL
- Source: git https://github.com/ccny-ros-pkg/imu_tools.git (branch: indigo)
Package Summary
Filter which fuses angular velocities, accelerations, and (optionally) magnetic readings from a generic IMU device into an orientation. Based on code by Sebastian Madgwick, http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms.
- Maintainer status: developed
- Maintainer: Martin Günther <martin.guenther1980 AT gmail DOT com>, Ivan Dryanovski <ivan.dryanovski AT gmail DOT com>
- Author: Ivan Dryanovski
- License: GPL
- Source: git https://github.com/ccny-ros-pkg/imu_tools.git (branch: jade)
Package Summary
Filter which fuses angular velocities, accelerations, and (optionally) magnetic readings from a generic IMU device into an orientation. Based on code by Sebastian Madgwick, http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms.
- Maintainer status: developed
- Maintainer: Martin Günther <martin.guenther1980 AT gmail DOT com>
- Author: Ivan Dryanovski <ivan.dryanovski AT gmail DOT com>
- License: GPL
- Source: git https://github.com/ccny-ros-pkg/imu_tools.git (branch: kinetic)
Package Summary
Filter which fuses angular velocities, accelerations, and (optionally) magnetic readings from a generic IMU device into an orientation. Based on code by Sebastian Madgwick, http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms.
- Maintainer status: developed
- Maintainer: Martin Günther <martin.guenther1980 AT gmail DOT com>, Ivan Dryanovski <ivan.dryanovski AT gmail DOT com>
- Author: Ivan Dryanovski
- License: GPL
- Source: git https://github.com/ccny-ros-pkg/imu_tools.git (branch: lunar)
Package Summary
Filter which fuses angular velocities, accelerations, and (optionally) magnetic readings from a generic IMU device into an orientation. Based on code by Sebastian Madgwick, http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms.
- Maintainer status: developed
- Maintainer: Martin Günther <martin.guenther1980 AT gmail DOT com>
- Author: Ivan Dryanovski <ivan.dryanovski AT gmail DOT com>
- License: GPL
- Source: git https://github.com/CCNYRoboticsLab/imu_tools.git (branch: melodic)
Package Summary
Filter which fuses angular velocities, accelerations, and (optionally) magnetic readings from a generic IMU device into an orientation. Based on code by Sebastian Madgwick, http://www.x-io.co.uk/node/8#open_source_ahrs_and_imu_algorithms.
- Maintainer status: developed
- Maintainer: Martin Günther <martin.guenther1980 AT gmail DOT com>
- Author: Ivan Dryanovski <ivan.dryanovski AT gmail DOT com>
- License: GPL
- Source: git https://github.com/CCNYRoboticsLab/imu_tools.git (branch: noetic)
Contents
Details
The imu_filter_madgwick package is used to filter and fuse raw data from IMU devices. It fuses angular velocities, accelerations, and (optionally) magnetic readings from a generic IMU device into an orientation quaternion, and publishes the fused data on the imu/data topic. The package has been tested using the raw data output of a Phidgets IMU (Spatial 3/3/3) device. The package is a wrapper of Sebastian Madgwick's IMU filter [1].
Supported devices
The filter should be general enough to use with any IMU which publishes angular velocities and linear accelerations (and optionally magnetic field).
It has been tested with:
Example
Here's an example of the non-ROS version of the code, courtesy of Sebastian Madgwick.
Todo: similar video from rviz.
ROS API
Two drivers are available: imu_filter_node and imu_filter_nodelet. Their parameters and topics are identical.
Subscribed Topics
imu/data_raw (sensor_msgs/Imu)- Message containing raw IMU data, including angular velocities and linear accelerations.
- [optional] Magnetic field vector; the type is either sensor_msgs/MagneticField or geometry_msgs/Vector3Stamped (deprecated), depending on the parameter use_magnetic_field_msg (see below)
Published Topics
imu/data (sensor_msgs/Imu)- The fused Imu message, containing the orientation.
Parameters
Dynamically Reconfigurable Parameters
See the dynamic_reconfigure package for details on dynamically reconfigurable parameters.- Gain of the filter. Higher values lead to faster convergence but more noise. Lower values lead to slower convergence but smoother signal. Range: 0.0 to 1.0
- Gyro drift gain (approx. rad/s). Range: -1.0 to 1.0
- Magnetometer bias (hard iron correction), x component. Range: -10.0 to 10.0
- Magnetometer bias (hard iron correction), y component. Range: -10.0 to 10.0
- Magnetometer bias (hard iron correction), z component. Range: -10.0 to 10.0
- Standard deviation of the orientation estimate. Range: 0.0 to 1.0
Not Dynamically Reconfigurable Parameters
- The world frame with respect to which the orientation is indicated (see REP-145). For historic reasons, the old default is "nwu" (North-West-Up). New deployments should use "enu". Valid values: "nwu", "enu", "ned".
- Whether to use the magnetic field data in the data fusion.
- If set to true, subscribe to the /imu/mag topic as a sensor_msgs/MagneticField; if set to false (deprecated), use geometry_msgs/Vector3Stamped.
- The parent frame to be used in publish_tf.
- 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.
- If set to true, publish transforms from imu_frame to fixed frame instead of the other way around.
- The dt to use; if 0.0 (default), compute dt dynamically from message headers.
- If set to true, publish a couple of debug topics.
- If set to true, don't publish a filtered orientation. Instead, publish the stateless estimate of the orientation based on the latest accelerometer (and optionally magnetometer) readings alone. Useful for debugging.
- If set to true, subtract the gravity vector from the acceleration field in the published IMU message.
References
[1] http://www.x-io.co.uk/open-source-imu-and-ahrs-algorithms/
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]