ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
2

About using imu_tools filters

asked 2016-11-22 05:31:00 -0500

toyoxx gravatar image

Hi. I have a simple question about the usage of the filters included in imu_tools (imu_complementary_filter & imu_filter_madgwick).

So far, I have succeeded in sending my IMU readings to ROS from an Arduino (at a rate of around 100Hz, publishing Accelerometer, Gyro and Magnetometer to ROS). Then, I created a node that takes that data and builds two messages (sensor_msgs::Imu and sensor_msgs::MagneticField respectively).

I put the accelerometer values in the linear_acceleration field, the gyro in the angular_velocity field and the magnetometer in the magnetic_field. Additionally, I fill the covariance_matrices with 0, as I have no information about the covariances. Finally, on the orientation field, as my IMU does not produce an orientation estimate, I don't modify it and set orientation_covariance[0]=-1 , as suggested in the message definition.

However, when I plot the results the orientation values seem to jump a lot between 0 and 1, even with the IMU resting on the desk. I also tested the rviz plugin, but the box moves crazily, and I don't know what else to do.

Any idea on what am I doing wrong? I assumed the filters would take the available data fuse it and estimate the orientation quaternion. Am I right?

I tried with both filters, and couldn't get the IMU to work/display properly. Am I suppose to provide an estimation of the orientation to the filters?

I'm running Ubuntu 16.04 with ROS kinetic, and the IMU I'm using is a I2C LSM9DS0 from Adafruit.

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
3

answered 2016-11-29 02:53:12 -0500

There is a bagfile with some example values in imu_filter_madgwick/sample/phidgets_imu_upside_down.bag. You can try playing back the bagfile to see how it looks like, and use rostopic echo or rqt_plot to look at the values there and visualize the result in RViz. The bagfile is from an IMU mounted on a moving robot, so basically only the yaw angle changes. There are also two more bagfiles in that directory.

I put the accelerometer values in the linear_acceleration field, the gyro in the angular_velocity field and the magnetometer in the magnetic_field. Additionally, I fill the covariance_matrices with 0, as I have no information about the covariances. Finally, on the orientation field, as my IMU does not produce an orientation estimate, I don't modify it and set orientation_covariance[0]=-1 , as suggested in the message definition.

That is all correct. The covariance matrices are not taken into account by the filters anyway.

Any idea on what am I doing wrong? I assumed the filters would take the available data fuse it and estimate the orientation quaternion. Am I right?

Yes, that is correct.

Am I suppose to provide an estimation of the orientation to the filters?

No, the filter will do that.

In your private email to me you also asked about the units in the message. They are as follows:

angular_velocity: radian/sec; please check that your gyros don't instead publish degree/sec.

linear_acceleration: m/s^2

magnetic field: Tesla. This is wrong in the bagfile above, which instead publishes Gauss (1 Gauss = 1e4 Tesla). However, this does not affect the result, since only the direction of the magnetic field vector is taken into account, not the scale.

Another thing: Start by setting the use_mag parameter to false. Once you get good results, you can set it back to true.

One more thing: imu_filter_madgwick and imu_complementary_filter are interchangable and do the same thing. However, while imu_complementary_filter is newer, imu_filter_madgwick is better tested and maintained, so I would start with that one. If you get the input values right for one filter, it should work for both.

edit flag offensive delete link more

Comments

@Martin Günther Is there a launch file or a yaml file where you edit the parameters? I couldn't find one. Or should I directly modify fields in imu_filter_ros.cpp?

lffox gravatar image lffox  ( 2017-07-11 13:05:21 -0500 )edit
1

You can write a normal launch file like this: https://github.com/ros-drivers/phidge... . The parameters are documented here: http://wiki.ros.org/imu_filter_madgwick

Martin Günther gravatar image Martin Günther  ( 2017-07-12 07:06:21 -0500 )edit

@martin-guenther Thanks a lot.

lffox gravatar image lffox  ( 2017-07-15 14:22:39 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2016-11-22 05:31:00 -0500

Seen: 4,339 times

Last updated: Nov 29 '16