<> <> ## AUTOGENERATED DON'T DELETE ## CategoryPackage == 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: [[http://www.phidgets.com/products.php?product_id=1056_0 | Phidgets Spatial 3/3/3]] == 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. {{{ #!clearsilver CS/NodeAPI sub { 0{ name = imu/data_raw type = sensor_msgs/Imu desc = Message containing raw IMU data, including angular velocities and linear accelerations. } 1{ name = imu/mag type = sensor_msgs/MagneticField desc = [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) } } pub { 0{ name = imu/data type = sensor_msgs/Imu desc = The fused Imu message, containing the orientation. } } # Autogenerated param section. Do not hand edit. param { group.0 { name=Dynamically Reconfigurable Parameters desc=See the [[dynamic_reconfigure]] package for details on dynamically reconfigurable parameters. 0.name= ~gain 0.default= 0.1 0.type= double 0.desc=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 1.name= ~zeta 1.default= 0.0 1.type= double 1.desc=Gyro drift gain (approx. rad/s). Range: -1.0 to 1.0 2.name= ~mag_bias_x 2.default= 0.0 2.type= double 2.desc=Magnetometer bias (hard iron correction), x component. Range: -10.0 to 10.0 3.name= ~mag_bias_y 3.default= 0.0 3.type= double 3.desc=Magnetometer bias (hard iron correction), y component. Range: -10.0 to 10.0 4.name= ~mag_bias_z 4.default= 0.0 4.type= double 4.desc=Magnetometer bias (hard iron correction), z component. Range: -10.0 to 10.0 5.name= ~orientation_stddev 5.default= 0.0 5.type= double 5.desc=Standard deviation of the orientation estimate. Range: 0.0 to 1.0 } # End of autogenerated section. You may edit below. group.1 { name=Not Dynamically Reconfigurable Parameters 0.name = ~world_frame 0.type = string 0.default = `"nwu"` for Indigo - Kinetic, `"enu"` for Lunar+ 0.desc = The world frame with respect to which the orientation is indicated (see [[https://github.com/paulbovbel/rep/blob/5b0c670130da8222ab28d5aba75dce5a26442ffe/rep-0145.rst | REP-145]]). For historic reasons, the old default is "nwu" (North-West-Up). New deployments should use "enu". Valid values: "nwu", "enu", "ned". 1.name = ~use_mag 1.type = bool 1.default = `true` 1.desc = Whether to use the magnetic field data in the data fusion. 2.name = ~use_magnetic_field_msg 2.type = bool 2.default = `false` for Hydro and Indigo, `true` for Jade+ 2.desc = If set to `true`, subscribe to the `/imu/mag` topic as a `sensor_msgs/MagneticField`; if set to `false` (deprecated), use `geometry_msgs/Vector3Stamped`. 3.name = ~fixed_frame 3.type = string 3.default = `odom` 3.desc = The parent frame to be used in `publish_tf`. 4.name = ~publish_tf 4.type = bool 4.default = `true` 4.desc = 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. 5.name = ~reverse_tf 5.type = bool 5.default = `false` 5.desc = If set to `true`, publish transforms from `imu_frame` to `fixed frame` instead of the other way around. 6.name = ~constant_dt 6.type = double 6.default = 0.0 6.desc = The dt to use; if 0.0 (default), compute dt dynamically from message headers. 7.name = ~publish_debug_topics 7.type = bool 7.default = `false` 7.desc = If set to `true`, publish a couple of debug topics. 8.name = ~stateless 8.type = bool 8.default = `false` 8.desc = 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. 9.name = ~remove_gravity_vector 9.type = bool 9.default = `false` 9.desc = 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. <> ## AUTOGENERATED DON'T DELETE ## CategoryPackage