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

inertia origin set in urdf handled wrong by gazebo?

asked 2012-02-09 00:12:40 -0500

Kai Bublitz gravatar image

updated 2012-02-14 23:28:53 -0500

Hi there,

I am currently developing an urdf model of our robot for simulation in gazebo. I always had problems setting the mass origin correctly. My model has a base_footprint link as root link, which has and so I didn't care about it's inertia origin, the child link is the base_link which is the main body of the robot, where I set the mass and origin values. I found out that gazebo (or the urdf converter?) is handling the model in a very strange way. The origin value of base_link is ignored and the origin for all (fixed) parts is the origin specified in base_footprint.

So now my question is how this is supposed to be? Is this wanted behaviour or a bug in gazebo? Or am I missing something? It took me weeks to figure out what exactly is the problem, and I couldn't find any information about this problem.

edit: Another question. Where should I specify the inertia values and how are they evaluated? e.g. what happens if I give an inertia matrix for both base_footprint and base_link at different origins?

UPDATE2: I removed my previous urdf, now here is a new example:

cube1.urdf:

<robot name="cube1">
    <link name="cube">
        <visual>
            <geometry>
                <box size="1 1 1"/>
            </geometry>
        </visual>
        <collision>
            <geometry>
                <box size="1 1 1"/>
            </geometry>
        </collision>
        <inertial>
            <mass value="10"/>
            <origin xyz="5 5 5" />
            <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
        </inertial>
    </link>
</robot>

cube2.urdf:

<robot name="cube2">
    <link name="cube">
        <visual>
            <geometry>
                <box size="1 1 1"/>
            </geometry>
        </visual>
        <collision>
            <geometry>
                <box size="1 1 1"/>
            </geometry>
        </collision>
        <inertial>
            <mass value="10"/>
            <origin xyz="5 5 5" />
            <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
        </inertial>
    </link>
    <link name="pseudo_link">
        <visual>
            <geometry>
                <box size="0.1 0.1 0.1"/>
            </geometry>
        </visual>
        <collision>
            <geometry>
                <box size="0.1 0.1 0.1"/>
            </geometry>
        </collision>
        <inertial>
            <mass value="0.00001"/>
            <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
        </inertial>
    </link>
    <joint name="cube_joint" type="fixed">
        <origin xyz="0 0 0" rpy="0 0 0" />
        <parent link="pseudo_link"/>
        <child link="cube"/>
    </joint>
</robot>

Both times it's a simple cube with 1m sides and a mass of 10kg. The mass origin has an offset of 5m in every direction, so it is outside of the geometry. cube2 has an additional pseudo link as parent which has a very small mass and its origin in the center. If gazebo handled the mass origin correctly I would expect both cubes to show the same behavior. If you spawn both models in gazebo you can see that cube1 starts standing on the corner, as expected, because the mass origin is outside. However cube2 is just laying on the floor as normal cubes do. So clearly the mass origin of ... (more)

edit retag flag offensive close merge delete

Comments

How are you measuring the mass origin?
DimitriProsser gravatar image DimitriProsser  ( 2012-02-09 00:45:27 -0500 )edit

I'm just guessing the mass origin so that it is somewhere in the center of the robot. I know that is not very accurate but it's good enough for what I need.

Kai Bublitz gravatar image Kai Bublitz  ( 2012-02-13 20:43:54 -0500 )edit

Well, how do you know that the mass origin is not being set correctly?

DimitriProsser gravatar image DimitriProsser  ( 2012-02-14 02:33:00 -0500 )edit

I can see it from the behavior in gazebo. When I choose such extreme values as in my example above the robot should fall to one side or the other, however it does not. I could try to make a more specific example to prove it (or prove myself wrong)

Kai Bublitz gravatar image Kai Bublitz  ( 2012-02-14 03:31:14 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
4

answered 2012-02-15 05:34:39 -0500

hsu gravatar image

updated 2012-02-22 17:13:01 -0500

Update: just released 1.4.11, should be a day or so before the debs are built.

Hi Kai, the problem is in the fixed joint reduction code in urdf2gazebo parser, ticketed here. A patch has been applied (see ticket), changes will be released with the next patch release. Thanks.

One way to see more details about this bug, you can edit your ~/.rosconsole so gazebo is set to DEBUG. Save your model with pseudo link (as t2.urdf), then run:

$ rosrun gazebo urdf2model -f t2.urdf -o t2.model
[DEBUG] [1329326366.171824770]: parsing gazebo extension
[DEBUG] [1329326366.171915322]: TREE: at [pseudo_link]
[DEBUG] [1329326366.171944564]: TREE: at [cube]
[DEBUG] [1329326366.171999736]: TREE:   extension lumping from [cube] to [pseudo_link]
[DEBUG] [1329326366.172026516]:   EXTENSION: Reference lumping from [cube] to [pseudo_link]
[DEBUG] [1329326366.172052313]: ====================================================================
[DEBUG] [1329326366.172074282]: ====================================================================
[DEBUG] [1329326366.172115979]: ====================================================================
[DEBUG] [1329326366.172160533]: ====================================================================
[DEBUG] [1329326366.172188838]: ====================================================================
[DEBUG] [1329326366.172209392]: ====================================================================
[DEBUG] [1329326366.172232357]: TREE:   mass lumping from [cube] to [pseudo_link]
[DEBUG] [1329326366.172264904]: LINK NAME: [pseudo_link] from dMass
[DEBUG] [1329326366.172300103]:      MASS: [0.000010]
[DEBUG] [1329326366.172323848]:        CG: [0.000000 0.000000 0.000000]
[DEBUG] [1329326366.172346809]:         I: [0.001000 0.000000 0.000000]
[DEBUG] [1329326366.172369745]:            [0.000000 0.001000 0.000000]
[DEBUG] [1329326366.172392519]:            [0.000000 0.000000 0.001000]
[DEBUG] [1329326366.172418484]: LINK NAME: [pseudo_link] from urdf::Link
[DEBUG] [1329326366.172463357]:      MASS: [0.000010]
[DEBUG] [1329326366.172500362]:        CG: [0.000000 0.000000 0.000000]
[DEBUG] [1329326366.172522955]:         I: [0.001000 0.000000 0.000000]
[DEBUG] [1329326366.172545376]:            [0.000000 0.001000 0.000000]
[DEBUG] [1329326366.172567982]:            [0.000000 0.000000 0.001000]
[DEBUG] [1329326366.172605268]: LINK NAME: [cube] from dMass
[DEBUG] [1329326366.172644066]:      MASS: [10.000000]
[DEBUG] [1329326366.172665388]:        CG: [5.000000 5.000000 5.000000]
[DEBUG] [1329326366.172687403]:         I: [0.001000 0.000000 0.000000]
[DEBUG] [1329326366.172708925]:            [0.000000 0.001000 0.000000]
[DEBUG] [1329326366.172742261]:            [0.000000 0.000000 0.001000]
[DEBUG] [1329326366.172787083]: LINK NAME: [cube] from urdf::Link
[DEBUG] [1329326366.172824148]:      MASS: [10.000000]
[DEBUG] [1329326366.172845650]:        CG: [5.000000 5.000000 5.000000]
[DEBUG] [1329326366.172867375]:         I: [0.001000 0.000000 0.000000]
[DEBUG] [1329326366.172900337]:            [0.000000 0.001000 0.000000]
[DEBUG] [1329326366.172949061]:            [0.000000 0.000000 0.001000]
[DEBUG] [1329326366.172987833]: debug: 0.000000 0.000000 0.000000
[DEBUG] [1329326366.173022669]: LINK NAME: [cube] from dMass
[DEBUG] [1329326366.173043504]:      MASS: [10.000000]
[DEBUG] [1329326366.173098877]:        CG: [5.000000 5.000000 5.000000]
[DEBUG] [1329326366.173120663]:         I: [0.001000 0.000000 0.000000]
[DEBUG] [1329326366.173142453]:            [0.000000 0.001000 0.000000]
[DEBUG] [1329326366.173164114]:            [0.000000 0.000000 0.001000]
[DEBUG] [1329326366.173195938]: LINK NAME: [cube] from dMass
[DEBUG] [1329326366.173216870]:      MASS: [10.000000]
[DEBUG] [1329326366.173246253]:        CG: [5.000000 5.000000 5.000000]
[DEBUG] [1329326366.173267903]:         I: [0.001000 0.000000 0.000000]
[DEBUG] [1329326366.173288764]:            [0.000000 0.001000 0.000000]
[DEBUG] [1329326366.173310421]:            [0.000000 0.000000 0.001000]
[DEBUG] [1329326366.173331826]: LINK NAME: [pseudo_link] from dMass
[DEBUG] [1329326366.173353029]:      MASS: [10.000010]
[DEBUG] [1329326366.173368923]:        CG: [4.999995 ...
(more)
edit flag offensive delete link more

Comments

Good to know. Do you know when the next bugfix-release will be?

Kai Bublitz gravatar image Kai Bublitz  ( 2012-02-22 00:06:15 -0500 )edit

Hi, is there some specific directory where we're supposed to create this ~/.rosconsole file?

rhow gravatar image rhow  ( 2020-07-28 07:04:40 -0500 )edit

Question Tools

Stats

Asked: 2012-02-09 00:12:40 -0500

Seen: 2,227 times

Last updated: Feb 22 '12