Gazebo | Ignition | Community
Ask Your Question
0

Model is unstable in Gazebo after adding inertial tag

asked 2019-11-09 10:23:46 -0600

yash gravatar image

updated 2019-11-11 04:38:48 -0600

kumpakri gravatar image

Hello, I am making a simple URDF for my project. I am finished with base_footprint and base_link. It seems like after adding the interial parameters to the robot, the robot became unstable after simulating in Gazebo. It started rotating about Z axis for some reason. I cannot find the solution to this. I would appreciate your help.

Code:

<?xml version="1.0" encoding="UTF-8"?>
<robot name="Auto_Bot">

    <material name="blue">
        <color rgba="0 0 0.8 1"/>
    </material>

    <material name="white">
        <color rgba="1 1 1 1"/>
    </material>

    <material name="red">
        <color rgba="1 0 0 1"/>
    </material>

    <link name="base_footprint"/>

    <joint name="base_joint" type="fixed">
        <parent link="base_footprint"/>
        <child link="base_link"/>
        <origin xyz="0 0 0.152" rpy="0 0 0"/>
    </joint>

    <link name="base_link">

        <visual>
            <geometry>
                <mesh filename="package://turtlebot3_description/meshes/Autonomous_Vehicle/meshes/V3_body_Assembly.stl" scale="0.01 0.01 0.01"/>
            </geometry>
            <material name="blue"/>
        </visual>

        <collision>
            <geometry>
                <mesh filename="package://turtlebot3_description/meshes/Autonomous_Vehicle/meshes/V3_body_Assembly.stl" scale="0.01 0.01 0.01"/>
            </geometry>
        </collision>

        <inertial>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <mass value="18.316"/>
            <inertia ixx="1.492" ixy="0.005" ixz="-0.012"
                     iyy="0.005" iyz="-0.012"
                     izz="-0.012"/>
        </inertial>

    </link>

</robot>
edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2019-11-15 14:52:09 -0600

Saimon gravatar image

It looks like the inertial moment are not well defined. I recommend to define only the diagonal moments of inertia (Ixx, Iyy, Izz), you can use the information form https://en.wikipedia.org/wiki/List_of... (that also suggest the gazebo tutorial). If the problem continues I suggest sending some pictures with the inertia that gazebo GUI show from your model.

edit flag offensive delete link more
0

answered 2019-11-11 08:14:54 -0600

elemecro gravatar image

updated 2019-11-11 08:15:08 -0600

Most probably, inertial values are not correct. change the values to

<inertia ixx="1" ixy="0" ixz="0"
         iyy="1" iyz="0"
         izz="1"/>

See the results and let me know...U can play with different mass values as well

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2019-11-09 10:23:46 -0600

Seen: 512 times

Last updated: Nov 15 '19