Restitution coefficient does not change
Hi all,
I'm creating a contact simulation of two objects with Gazebo7. I tried to change the restitution coefficient, but still I can't make it.
My URDF code is here:
Ball:
<link name="ball_link">
<visual name="ball_visual">
<origin xyz="$0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://single_model/urdf/ball/meshes/ball.dae"/>
<scale>0.1 0.1 0.1</scale>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://single_model/urdf/ball/meshes/ball.dae"/>
<scale>0.1 0.1 0.1</scale>
</geometry>
<surface>
<bounce>
<restitution_coefficient>0.5</restitution_coefficient>
<threshold>0.01</threshold>
</bounce>
</surface>
</collision>
<inertial>
<mass value="${ball_mass}"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="${ball_ixx}"
ixy="${ball_ixy}"
ixz="${ball_ixz}"
iyy="${ball_iyy}"
iyz="${ball_iyz}"
izz="${ball_izz}"/>
</inertial>
</link>
Target:
<link name="target_link">
<visual name="target_visual">
<origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://single_model/urdf/target/meshes/box.dae"/>
<scale>0.1 0.1 0.1</scale>
</geometry>
</visual>
<collision>
<origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://single_model/urdf/target/meshes/box.dae"/>
<scale>0.1 0.1 0.1</scale>
</geometry>
<surface>
<bounce>
<restitution_coefficient>0.5</restitution_coefficient>
<threshold>0.01</threshold>
</bounce>
</surface>
</collision>
<inertial>
<mass value="${target_mass}"/>
<origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
<inertia ixx="${target_ixx}"
ixy="${target_ixy}"
ixz="${target_ixz}"
iyy="${target_iyy}"
iyz="${target_iyz}"
izz="${target_izz}"/>
</inertial>
</link>
And gazebo.xacro is here:
Ball:
<gazebo reference="ball_link">
<selfCollide>true</selfCollide>
<maxVel>10.0</maxVel>
<minDepth>0.001</minDepth>
</gazebo>
Target:
<gazebo reference="target_link">
<selfCollide>true</selfCollide>
<maxVel>10.0</maxVel>
<minDepth>0.001</minDepth>
</gazebo>
When I perform this simulation, both two objects' restitution coefficient are still 0, and they start bounding in the world.
I would really appreciate you if you would give me some advice.
urdf? restitution coefficient isn't part of urdf as far as a I know. What happens if you write it directly in SDF? here's an example: https://bitbucket.org/osrf/gazebo_models/src/ca53b7f6b22c2c426c240aa00fb4a8cf23c728d5/frc2016_ball/model.sdf?at=default&fileviewer=file-view-default you may have to put the restitution_coefficient in a <gazebo> tag
Thank you very much! I changed my URDF into SDF, then now it works well.