Why do the wheels move away from joint when the robot falls over in gazebo?
The wheels seem to fall of the robot when it falls over in gazebo. When the model is first spawned the wheels seem to be in the correct position but when it falls over it looks like they detach. Any help for why this happens/ how to fix it would be much appreciated. Many thanks
The code/markup used is below:
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="self balancing robot">
<link name="base">
<visual>
<origin xyz="0 0 0.2" />
<geometry>
<box size="0.1 0.2 0.3"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0.2" />
<geometry>
<box size="0.1 0.2 0.3"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0.2" />
<mass value="2"/>
<inertia ixx="0.4" ixy="0.0" ixz="0.0" iyy="0.4" iyz="0.0" izz="0.2"/>
</inertial>
</link>
<link name="right_wheel">
<visual>
<origin xyz="0 0.12 0.05" rpy="${pi/2} 0 0" />
<geometry>
<cylinder length="0.04" radius="0.05"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0.12 0.05" rpy="${pi/2} 0 0" />
<geometry>
<cylinder length="0.04" radius="0.05"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0.12 0.05" rpy="${pi/2} 0 0" />
<mass value="2"/>
<inertia ixx="0.4" ixy="0.0" ixz="0.0" iyy="0.4" iyz="0.0" izz="0.2"/>
</inertial>
</link>
<link name="left_wheel">
<visual>
<origin xyz="0 -0.12 0.05" rpy="${pi/2} 0 0" />
<geometry>
<cylinder length="0.04" radius="0.05"/>
</geometry>
</visual>
<collision>
<origin xyz="0 -0.12 0.05" rpy="${pi/2} 0 0" />
<geometry>
<cylinder length="0.04" radius="0.05"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 -0.12 0.05" rpy="${pi/2} 0 0" />
<mass value="2"/>
<inertia ixx="0.4" ixy="0.0" ixz="0.0" iyy="0.4" iyz="0.0" izz="0.2"/>
</inertial>
</link>
<joint name="lwj" type="continuous">
<parent link="base"/>
<child link="left_wheel"/>
<origin xyz="0 0 0" />
<axis xyz="0 1 0"/>
</joint>
<joint name="rwj" type="continuous">
<parent link="base"/>
<child link="right_wheel"/>
<origin xyz="0 0 0" />
<axis xyz="0 1 0"/>
</joint>
</robot>