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

IMU plugin erratic acceleration measurements

asked 2015-09-08 14:52:27 -0600

Jacob Lambert gravatar image

updated 2015-09-08 19:16:00 -0600

Hi,

I am trying to use the IMU plugin in Gazebo (v2.2.5) but am seeing weird behavior. I am running the IMU without biases or noise, and the acceleration/rate outputs integrate to trajectories I expect, but the measurements are nevertheless erratic: they are constantly switching sign. I publish sinusoidal velocities in gazebo so I know what to expect from the acceleration measurements, but they look like this:

Whole dataset (a_x, a_y, w)

Zoomed in

I don't expect perfectly smooth trajectories but 50m/s^2 accels at times seems too unstable, something must be wrong. If I just look at the gravity vector in rviz it jumps all over the place. I tried to set everything to zero...

<!-- Chassis -->
    <link name="base_link">
        <inertial>
            <mass value="10.0"/>
            <origin xyz="0 0 0.177"/>
            <inertia 
                 ixx="0.3338" ixy="0.0" ixz="0.0"
                 iyy="0.4783" iyz="0.0"
                 izz="0.3338"/>
        </inertial>
        <visual name="base_visual">
            <origin xyz="0 0 0.177" rpy="0 0 0"/>
            <geometry name="pioneer_geom">
                <mesh filename="package://dopebot_description/meshes/chassis.stl"/>
            </geometry>
            <material name="ChassisRed">
                <color rgba="0.851 0.0 0.0 1.0"/>
            </material>
        </visual>
        <collision>
            <origin xyz="0 0 0.177" rpy="0 0 0"/>
                <geometry>
                    <mesh filename="package://dopebot_description/meshes/chassis.stl"/>
                </geometry>
        </collision>
    </link> 

<!-- IMU -->
<link name="imu_link">
  <inertial>
    <mass value="0.001"/>
    <origin rpy="0 0 0" xyz="0 0 0"/>
    <inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
  </inertial>

  <visual>
    <origin rpy="0 0 0" xyz="0 0 0"/>
    <geometry>
      <box size="0.1 0.1 0.1"/>
    </geometry>
  </visual>

  <collision>
    <origin rpy="0 0 0" xyz="0 0 0"/>
    <geometry>
      <box size="0.1 0.1 0.1"/>
    </geometry>
  </collision>
</link>

<!-- IMU Joint -->
  <joint name="imu_joint" type="fixed">
    <axis xyz="1 0 0"/> <!-- 0 1 0 -->
    <origin xyz="0 0 0.28"/>
    <parent link="base_link"/>
    <child link="imu_link"/>
  </joint>

      <plugin name="imu_plugin" filename="libhector_gazebo_ros_imu.so">
            <updateRate>1000</updateRate>
            <bodyName>base_link</bodyName>
            <topicName>/imu</topicName>
            <serviceName>/imu/calibrate</serviceName>
            <accelOffset>0.0 0.0 0.0</accelOffset>
            <accelDrift>0.0 0.0 0.0</accelDrift>
            <accelDriftFrequency>0.0 0.0 0.0</accelDriftFrequency>
            <accelGaussianNoise>0.0 0.0 0.0</accelGaussianNoise>
            <rateOffset>0.0 0.0 0.0</rateOffset>
            <rateDrift>0.0 0.0 0.0</rateDrift>
            <rateDriftFrequency>0.0 0.0 0.0</rateDriftFrequency>
            <rateGaussianNoise>0.0 0.0 0.0</rateGaussianNoise>
            <headingOffset>0.0</headingOffset>
            <headingDrift>0.0</headingDrift>
            <headingDriftFrequency>0.0</headingDriftFrequency>
            <headingGaussianNoise>0.0</headingGaussianNoise>
            <rpyOffset>0.0 0.0 0.0</rpyOffset>
            <xyzOffset>0.0 0.0 0.0</xyzOffset>
            <gaussianNoise>0.0</gaussianNoise>
        </plugin>

but the problem remains. Any ideas?

Thank you,

Jacob

edit retag flag offensive close merge delete

Comments

1

+1. Noticed the same thing on my end.

l0g1x gravatar image l0g1x  ( 2015-09-08 16:04:46 -0600 )edit
1

Can you update your question with which gazebo version your running? And would you also mind attaching a code snippet of the link that you attach the imu plugin to, as well as any links/joints related?

l0g1x gravatar image l0g1x  ( 2015-09-08 16:06:31 -0600 )edit

Updated. I guess you had no luck fixing it? I tried finding a model that includes a hector IMU but could not find one. I haven't seen any examples out there, just this guy who seems to have managed to get it to behave

Jacob Lambert gravatar image Jacob Lambert  ( 2015-09-08 19:19:12 -0600 )edit
1

The jackal simulation model from clearpath uses it.

l0g1x gravatar image l0g1x  ( 2015-09-09 13:50:59 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
3

answered 2015-09-09 01:53:44 -0600

This could be related to interplay between your model and Gazebo's (real-time) physics engine. Simulating dynamics is difficult and doing so in real-time requires a trade-off of speed vs. fidelity. It might be the case that your model indeed jitters at high frequency. I also often observed high noise in joint velocities (and thus, also accelerations) for complex robot models. You can decrease the physics engine step size and increase iterations from the Gazebo GUI. If things look better after you do so, the underlying simulation is indeed the cause. You then have the choice of either running simulation with these parameters (which will be slow), or trying to modify your model so there is less noise in simulation. The latter can be an art however and involves tweaking masses and inertias (and their relative magnitudes) while trying not to modify it too much.

edit flag offensive delete link more

Comments

I thought it might be something like that but wasn't sure what to do about it. I'll see how much I can mitigate these effects and report back. TY

Jacob Lambert gravatar image Jacob Lambert  ( 2015-09-09 12:39:43 -0600 )edit

This actually makes sense, as another simulation i have uses the skid steer plugin for 4 wheels has no issue with the hector imu plugin, but the model i have issues with is 6 wheels. hector's 6w plugin doesnt work on gz5, so i have to use the skid steer plugin, leaving two wheels free to move. Thx!

l0g1x gravatar image l0g1x  ( 2015-09-09 13:54:41 -0600 )edit

Decreased step size dramatically, increased number of iterations. Gravity vector is well behaved but accelerations in the plane are still crazy. Played around with the model but it didn't seem to help, I'll take a look at how the Jackal does it.

Jacob Lambert gravatar image Jacob Lambert  ( 2015-09-09 14:30:44 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2015-09-08 14:50:34 -0600

Seen: 2,683 times

Last updated: Sep 09 '15