DFKI-NI / mir_robot

ROS support for the MiR Robots. This is a community project to use the MiR Robots with ROS. It is not affiliated with Mobile Industrial Robots.
BSD 3-Clause "New" or "Revised" License
231 stars 157 forks source link

imu noise of mir #99

Closed narutojxl closed 2 years ago

narutojxl commented 2 years ago

Hello authors,
Thanks for your sharing this interesting software. I'm using your mir_robot noetic branch. When remaining the default imu noise params <xacro:property name="imu_stdev" value="0.00017" /> of mir_100_v1.urdf.xacro, which loads imu.gazebo.urdf.xacro and sets <xacro:imu_gazebo link="${prefix}imu_link" imu_topic="/imu/data" update_rate="50.0" stdev="${imu_stdev}" />. imu's gaussianNoise =0.00017 * 0.00017 is very very small.

ax_ay az wx_wy wz

mintar commented 2 years ago

Almost all of that noise does not come from the gaussianNoise parameter, but is unintentional. Here's a plot of your experiment (rotating robot) where I set gaussianNoise = 0:

image

It looks almost identical to your plot. The noise is the same when the robot is stationary. I think this is because even when the robot is stationary in Gazebo, there are always small corrections being applied. There are a lot of simulated forces at work: there is a repulsive force between the ground and each of the wheels; the powered wheels are being commanded to turn forwards and backwards to keep them still, and so on. All of this leads to the robot to "vibrate" by a minuscule amount. Unfortunately, the gazebo_ros_imu_sensor implementation just reads the instantaneous linear accelerations and angular velocities and returns those. What it should do is calculate the mean for each sampling period (the plugin is updated at 1000 Hz, but only publishes at 50 Hz).

Apart from that, the gazebo_ros_imu_sensor implementation of noise is just plain horrible. There's only one parameter (gaussianNoise) that's applied equally to orientation (as a unitless quaternion), linear acceleration (in m/s²) and angular velocity (in rad/s). Instead, it should at least have these parameters:

... and possibly also:

Then the total noise can be properly calculated like this:

import numpy as np

# n: number of measurements
# dt: sampling rate [s], e.g. dt = 1e-2 when sampling at 100 Hz
def generate_signal(n, dt, noise_density, random_walk, random_state=0):
    rng = np.random.RandomState(random_state)
    white = noise_density / np.sqrt(dt) * rng.randn(n)
    walk = random_walk * np.sqrt(dt) * np.cumsum(rng.randn(n))
    return white + walk

The orientation should probably be either not filled at all or be returned without noise, because in order to be realistic, it should be coupled to the gyroscope and accelerometer noise. There are already packages like imu_filter_madgwick that compute the orientation from gyro and accelerometer data, but it doesn't make sense to replicate that here.

So in short: If you want to get rid of the noise, you'll have to improve gazebo_ros_imu_sensor!

narutojxl commented 2 years ago

Hi @mintar, thanks for your very kind and detailed reply!
Without adding allan variance noise(noise density and random walk) and without adding gaussianNoise, according to your advance, i calculate acc and gyro by averaging for each sampling period, the noise is smaller than the instantaneous ones as we expected, although it still is a little noisy. I agree with you the noisy data is caused by gazebo simulating previously mentioned forces.
There is also a interesting thing, we send command is vx = 0, wz=0.4 rad/s, but the wz's mean is 0.425 rad/s measured by imu. Thanks again! Here are some test pictures. The order is accx&&_acc_y, acc_z, wz. acc_x_ acc_y az wz

mintar commented 2 years ago

Maybe you should try this IMU plugin instead:

It looks much better!

If you successfully use it, please report back!

narutojxl commented 2 years ago

Hi @mintar, thanks for your suggestions. I compare mir and husky, and compare libgazebo_ros_imu_sensor.so and libhector_gazebo_ros_imu.so with the same noise param. Because huksy wheel skidding when performing rotation in place, see here, so in the following 4 tests, i only send rostopic pub /cmd_vel geometry_msgs/Twist -r 3 -- '[0.4,0,0]' '[0, 0, 0]' to let robot forward.

mir_vx=0 4_wz=0_libgazebo_ros_imu_sensor

husky_vx=0 4_wz=0_libgazebo_ros_imu_sensor

mir_vx=0 4_wz=0_libgazebo_ros_imu_sensor mir_vx=0 4_wz=0_libhector_gazebo_ros_imu

mintar commented 2 years ago

Thank you for the detailed analysis! I've debugged and solved the problem in commit 063d4e7. The problem was that I used STL meshes as collision geometries for the wheels. If you visualize contacts in Gazebo, you can see that there are lots of inconsistent contacts (not all 6 wheels touch the ground at all times), which lead to these simulated "vibrations" of the robot, which was picked up by the simulated IMU:

https://user-images.githubusercontent.com/320188/145568395-f070f2b3-956e-4728-9845-591e7580d863.mp4

The husky doesn't have this problem:

https://user-images.githubusercontent.com/320188/145568447-6d372f39-4a94-43b1-86d8-d26ac0b57c12.mp4

After replacing the collision geometries with cylinders, the problem is fixed for the MiR:

https://user-images.githubusercontent.com/320188/145568522-9c4b1434-92ba-48b7-9e41-a2cc5cb2ca92.mp4

mintar commented 2 years ago

By the way, you should use -r 10 (or larger) instead of -r 3 in your rostopic pub calls, otherwise the Husky will brake and accelerate repeatedly.

mintar commented 2 years ago

I've also switched to the hector_gazebo_plugins now.

narutojxl commented 2 years ago

Hi author @mintar, thanks very much :)