Robot joint detaches when simulation is loaded
I'm trying to simulate a simple 4 DOF robot using gazebo. The robot has 3 revolute joints and 1 prismatic joint. The link named "wall_link" is fixed to the world. I've created the MYROBOT_description and MYROBOT_gazebo packages using the following tutorial.
However, when I run the simulation the prismatic and the first revolute joints simply detach from the fixed link and float away. No warnings or errors pop up when the simulation launch file is loaded (snippets of the launch file in the terminal and the code are attached). Here are the fixes that I have tried until this point (none of these have worked):
- Rechecked whether the inertial tag in each link is defined and accurate
- Checked the joints and whether the child / parent links are properly defined
- Tried adding a self_collide tag for the links to see if that fixes it
Can someone please help me out with this?
Terminal output when launch file is run
Before Running (while paused)
After Running (after unpausing)
The URDF file is as follows:
<?xml version="1.0" encoding="utf-8"?>
<robot name="r3">
<link name="world"/>
<joint name="fixed" type="fixed"> <parent link="world"/> <child link="wall_link"/> </joint>
<link name="wall_link">
<inertial>
<origin
xyz="-1.3668E-17 0.3 0.00020351"
rpy="0 0 0" />
<mass
value="18.067" />
<inertia
ixx="0.5559"
ixy="-4.6489E-21"
ixz="-4.3369E-18"
iyy="0.15"
iyz="7.5132E-22"
izz="0.6759" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://r3_description/meshes/wall_link.STL" />
</geometry>
<material
name="">
<color
rgba="1 1 1 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://r3_description/meshes/wall_link.STL" />
</geometry>
</collision>
</link>
<link name="linear_rail">
<inertial>
<origin
xyz="-4.1743E-15 0.0085192 -0.016"
rpy="0 0 0" />
<mass
value="0.011057" />
<inertia
ixx="1.4641E-06"
ixy="5.4276E-21"
ixz="4.8907E-22"
iyy="3.7337E-06"
iyz="-2.9124E-22"
izz="3.7228E-06" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://r3_description/meshes/linear_rail.STL" />
</geometry>
<material
name="">
<color
rgba="0.75294 0.75294 0.75294 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://r3_description/meshes/linear_rail.STL" />
</geometry>
</collision>
</link>
<joint name="rail_joint" type="prismatic"> <origin xyz="0 -0.066 0.284" rpy="3.1416 0 0"/> <parent link="wall_link"/> <child link="linear_rail"/> <axis xyz="0 0 -1"/> <limit lower="-0.2" upper="0.2" effort="10" velocity="5"/> </joint>
<link name="thigh_link">
<inertial>
<origin
xyz="9.8897E-05 -0.072814 0.00035302"
rpy="0 0 0" />
<mass
value="0.18426" />
<inertia
ixx="0.00011096"
ixy="-2.6884E-10"
ixz="8.301E-14"
iyy="4.5179E-05"
iyz="-1.6755E-07"
izz="9.3875E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://r3_description/meshes/thigh_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy ...
hello, did you try with a smaller simulation timestep ?