Model is unstable in Gazebo after adding inertial tag
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>