Project

General

Profile

Actions

Bug #342

open

poor acceleration estimate when sitting on the ground

Added by Martin Jacquet almost 3 years ago. Updated over 2 years ago.

Status:
New
Priority:
Normal

Description

I am getting weird data from the IMU when the uav is sitting on the floor in simuation.

I am building a visual/inertial state estimator that uses tags and IMU, and I am performing tests with the UAV steady to see whether the visual odometry drifts.

However, in that case what I read from the IMU (through rotorcraft) is either 4.12183 or 15.4982 for the acceleration along z.
The other data seems more correct, even though there are very noisy.
(See the logfile at https://cloud.laas.fr/index.php/s/eE17vJhWL8ErUx5 )

When hovering the IMU data are much cleaner (https://cloud.laas.fr/index.php/s/K2LxZkRoagpHbHP ).

I this intended/normal to read bad data when not flying? I would expect Gazebo to provide very precise data of steady models, so there might be something in mrsim-gazebo (or libmrsim for all I know, though I never observed this with a real platform).

Actions #1

Updated by Anthony Mallet almost 3 years ago

First, there is a default gaussian noise on the IMU with a 0.02 m/s²
standard deviation, to simulate a realistic IMU. It's currently
hardcoded in mrsim-gazebo, so if you need to tune it I could add a
parameter for that. But what you are seeing on Z is much bigger than
that, so this is not the cause of your issue.

I remember also seeing high IMU noise when the robot was touching the
floor. When I investigated this, I found that the contact model in
gazebo was really poor and was introducing high frequency oscillations
on the robot (it was oscillating with a Z alternating between "minus
something small" and "plus something small" around 0). Thus the
acceleration returned by the physics engine was affected, as the
acceleration is only determined by differenciation of the position (as
fas as I remember, but I may be wrong).

I then found that adding three small spheres to the body was improving
the situation (hence this:
https://git.openrobots.org/projects/mrsim-gazebo/repository/mrsim-gazebo/revisions/master/entry/models/mrsim-tilthex/model.sdf#L21)

If you are using your own model, do you have those "magic" spheres?

Maybe the "material" of those contact spheres could be changed, to
simulate something softer and see if this would damp those
oscillations. I think I tried that already (but I forgot the results
...). I gave up anyway because I thought that we were more interested
in actually flying in simulation rather than simulating contacts with
this engine not suited for that :)

You may also try to manually move the object and let it fall again, to
see if that changes the noise.

Actions #2

Updated by Martin Jacquet almost 3 years ago

I am using the model from openrobots with the 3 spheres.

I tried to have the UAV model static in gazebo to check the output of rotorcraft, which should get perferctly 0 acceleration from Gazebo.
I observe noise on the gyro (std 0.0028 on each axis, is this the expected value?) but the accelerometer read perfectly 0 (see https://cloud.laas.fr/index.php/s/ROWvMSdJh8Qy0PM ) instead of 0.2.

When hovering (supposedly steadily but with inevitable oscillations), I observe stds of: ~0.018 on the 3 gyro axis, ~0.12 on ax and ay and 0.0525 on az.
This is closer to "usable" values, even though the acceleration on x an y are quite large, I will increase the stds given to rotorcraft as calibration for the simulated UAV.

I would like to use POM to test how good it estimates the state using only IMU measurements (I expect drifting but I would like to have an idea of "how fast" it drifts), is there a way to do so?
I assume that their is no initial value (e.g. (0,0,0) position and (1,0,0,0) quaternion) so if no position or attitude are ever given, we would have random values for those.

Actions #3

Updated by Anthony Mallet almost 3 years ago

I'm sorry, your reply is confusing me :)

Are you still talking about high noise on the accelerometer when the
robot is on the ground? I don't see how you can get 0 from the
accelerometer in this case. First, there should be the default noise,
and it should read 9.81 on Z rather than 0. Is that your actual issue?

(otherwise yes, the default stddev for the gyroscopes is 3e-3).

I would like to use POM to test how good it estimates the state
using only IMU measurements

mrsim-gazebo has absolutely no connection with other components, you
need to deploy at least rotorcraft-genom3 in order to make sense of the
data and export that in a more complete software architecture, but
this is off-topic here.

Basically, you can only estimate the roll and pitch with an IMU. The
position will look like a double integration of gaussian noise, so the
variance will grow like the cube of the time, which makes it useless
in practice.

Actions #4

Updated by Martin Jacquet almost 3 years ago

Sorry I made a confusing answer, I'll try to clarify it.

Are you still talking about high noise on the accelerometer when the
robot is on the ground? I don't see how you can get 0 from the
accelerometer in this case. First, there should be the default noise,
and it should read 9.81 on Z rather than 0. Is that your actual issue?

I wanted to check if the weird accelerations values on the IMU came from the contact with the ground, or if the large noise was somehow added in the processing of the data.
I used the static option of Gazebo models ( https://osrf-distributions.s3.amazonaws.com/sdformat/api/1.5.html#static103 ) that basically makes it not movable, so my guess was that mrsim-gazebo would be reading 0 avel/acc from the Gazebo engine.
Hence, I would observe only the extra noise on the IMU. It seems to be the case for the angular velocities, but not for the acceleration, which read perfectly 0 in the log file I linked.
I don't know if this underlines a potential problem in mrsim-gazebo, but I figured I could point it out here.

mrsim-gazebo has absolutely no connection with other components, you
need to deploy at least rotorcraft-genom3 in order to make sense of the
data and export that in a more complete software architecture, but
this is off-topic here.

Basically, you can only estimate the roll and pitch with an IMU. The
position will look like a double integration of gaussian noise, so the
variance will grow like the cube of the time, which makes it useless
in practice.

My point was to check whether there was some issue in the IMU data coming from mrsim-gazebo by checking how well we could estimate the state with them.
I understand from your last sentence that this is not a very realistic idea :)

Actions #5

Updated by Anthony Mallet almost 3 years ago

On Wednesday 26 Jan 2022, at 13:53, Martin Jacquet wrote:

I wanted to check if the weird accelerations values on the IMU came
from the contact with the ground, or if the large noise was somehow
added in the processing of the data.

Yes, the noise comes from the contact with the ground. But I don't see
it myself anymore with the quadrotor model that has the three spheres
to make the contact stable.

I used the static option of Gazebo models, so my guess was that
mrsim-gazebo would be reading 0 avel/acc from the Gazebo engine.

It seems to be a bug or at least some unexpected effect of the static
property. The physics engine returns NaN for a static model, which
does not make sense. I commited a workaround in 23b8b55889.

Actions #6

Updated by Martin Jacquet almost 3 years ago

Yes, the noise comes from the contact with the ground. But I don't see
it myself anymore with the quadrotor model that has the three spheres
to make the contact stable.

I am using this model of the quadrotor with the 3 contact spheres https://git.openrobots.org/projects/mrsim-gazebo/repository/mrsim-gazebo/revisions/master/entry/models/mrsim-quadrotor/model.sdf#L19
When replacing the contact spheres with the ones from the tilthex model https://git.openrobots.org/projects/mrsim-gazebo/repository/mrsim-gazebo/revisions/master/entry/models/mrsim-tilthex/model.sdf#L21 the noise on az disappears. However changing the positions of these spheres (eg reduce the z offset to have them closer to the body) makes the values crazy again.
I tried a couple of combinaisons and I don't see any why this set of sphere positions is able to stabilize the contact while the others are not. (Just in case, I am using Gazebo 9.0.0)

Anyway, this is a problem you are already aware of and there is no obvious solution to it. And as you say, we are more interested in having the drones flying than sitting on the ground :)
We could probably close the issue.

Actions #7

Updated by Anthony Mallet almost 3 years ago

Yes, this is a frustrating. Playing with the inertia also changes the
behaviour, but nothing is repeatable. E.g. after some motion the
unstability appears or disappears.

I will not close the issue since it's not solved, but I have no more
clue to help with this ...

Actions #8

Updated by Anthony Mallet over 2 years ago

It seems that increasing the iterations of the physics solver helps.
E.g. going from 50 (default) to 500.

Actions

Also available in: Atom PDF