Links falling apart around origin when simulation is running. Low inertia?
Hello All
Barely getting started with Gazebo (7.0 running on Xenial) and here is my issue: i am modelling a finger, so very small parts with inertia as low as ixy="3.76912e-12" witch i have read could be the cause of the issue. If i load the model with the simulation stopped i get a vertical finger. However as soon as i start the simulation the parts "fall" around the origin. It seems the joint offsets are no longer being applied. I did a few tests to see if i could debug the issue and got the following results:
Using much larger inertia values the problem disappears (but no longer a realistic model). If i delete the top two segments and leave just the bottom two (and their joint) the problem does not occur. If i change simulation steps from the default 0,001000 to 0,000100 the problem stops (but very slow simulation). Also tried high values for joint damping and friction but did not seem to make a difference.
Is there anything i can do to get model working with the correct values?
Thank you
<robot name="finger">
<link name="base_link" />
<link name="base8">
<inertial>
<origin xyz="-1.26773e-06 0.000427739 0.00546823" rpy="0 0 0"/>
<mass value="0.00171993"/>
<inertia ixx="4.15282e-08" ixy="3.76912e-12" ixz="3.81441e-12" iyy="9.2702e-08" iyz="-1.64114e-09" izz="9.15731e-08"/>
</inertial>
<visual>
<origin xyz="0 0 0.0114743" rpy="0 0 0"/>
<geometry>
<mesh filename="package://finger_description/meshes/base8_ipt_11dce11d.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="base8_color">
<color rgba="0.74902 0.74902 0.74902 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0.0114743" rpy="0 0 0"/>
<geometry>
<mesh filename="package://finger_description/meshes/base8_ipt_11dce11d.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="finger_segment1">
<inertial>
<origin xyz="0.00449723934 0.00021284299985 0.0071977" rpy="0 0 0"/>
<mass value="0.00199166"/>
<inertia ixx="1.06576e-07" ixy="1.37509e-11" ixz="3.64504e-11" iyy="1.21654e-07" iyz="-3.77147e-09" izz="5.43651e-08"/>
</inertial>
<visual>
<origin xyz="0.0045 -1.77523001664e-05 0.008" rpy="0 0 0"/>
<geometry>
<mesh filename="package://finger_description/meshes/finger_segment_ipt_544d6e46.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="finger_segment1_color">
<color rgba="0.74902 0.74902 0.74902 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0.0045 -1.77523001664e-05 0.008" rpy="0 0 0"/>
<geometry>
<mesh filename="package://finger_description/meshes/finger_segment_ipt_544d6e46.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<joint name="finger_segment1__base8" type="continuous">
<origin xyz="-0.0045 0 0.0114743" rpy="0 0 0"/>
<axis xyz="1.0 0.0 0.0"/>
<parent link="base8"/>
<child link="finger_segment1"/>
<dynamics damping="1" friction="1"/>
</joint>
<link name="finger_segment2">
<inertial>
<origin xyz="0.00449723934 0.000212842999506 0.0071977" rpy="0 0 0"/>
<mass value="0.00199166"/>
<inertia ixx="1.06576e-07" ixy="1.37509e-11" ixz="3.64504e-11" iyy="1.21654e-07" iyz="-3.77147e-09" izz="5.43651e-08"/>
</inertial>
<visual>
<origin xyz="0.0045 -1.77523005075e-05 0.008" rpy="0 0 0"/>
<geometry>
<mesh filename="package://finger_description/meshes/finger_segment_ipt_544d6e46.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="finger_segment2_color">
<color rgba="0.74902 0.74902 0.74902 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0.0045 -1.77523005075e-05 0.008" rpy="0 0 0"/>
<geometry>
<mesh filename="package://finger_description/meshes/finger_segment_ipt_544d6e46.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<joint name="finger_segment2__finger_segment1" type="continuous">
<origin xyz="0 0 0.018" rpy="0 0 0"/>
<axis xyz="1.0 0.0 0.0"/>
<parent link="finger_segment1"/>
<child link="finger_segment2"/>
<dynamics damping="1" friction="1"/>
</joint>
<link name="tip">
<inertial>
<origin xyz="0.004500186539 0.0001604209997 0.00787229999999" rpy="0 0 0"/>
<mass value="0.0025752"/>
<inertia ixx="1.13686e-07" ixy="1.11636e-11" ixz="5.21811e-12" iyy="1.23658e-07" iyz="-3.05198e-09" izz="5.44323e-08"/>
</inertial>
<visual>
<origin xyz="0.0045 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://finger_description/meshes/tip_ipt_3a5e0dea.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="tip_color">
<color rgba="0.74902 0.74902 0.74902 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0.0045 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://finger_description/meshes/tip_ipt_3a5e0dea.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<joint name="tip__finger_segment2" type="continuous">
<origin xyz="0 0 0.018" rpy="0 0 0"/>
<axis xyz="1.0 0.0 0.0"/>
<parent link="finger_segment2"/>
<child link="tip"/>
<dynamics damping="1" friction="1"/>
</joint>
<joint name="base_joint" type="fixed" >
<parent link="base_link" />
<child link="base8" />
<origin xyz="0 0 0" rpy="0 0 0" />
</joint>
</robot>
Asked by Ironic on 2018-08-19 20:10:05 UTC
Comments