how do i add torsional friction to urdf model
how do i add torsional friction to urdf model
how do i add torsional friction to urdf model
Create a <gazebo>
tag which references the URDF link and contains a <collision name="...">
with a name matching the generated SDF collision. In simple cases the name is the link's name + _collision
. However, this isn't always the case (fixed joint lumping changes the collision name) so I recommend loading the URDF into gazebo and using the GUI left panel to figure out the actual name of the generated SDF collision.
Here is an example of torsional friction on a 1x1x1m cube defined in URDF.
<?xml version="1.0" ?>
<robot name="my_robot">
<link name="some_link">
<inertial>
<mass value="0.5"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.083" ixy="0.0" ixz="0.0" iyy="0.083" iyz="0.0" izz="0.083"/>
</inertial>
<visual>
<geometry>
<box size="1 1 1"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="1 1 1"/>
</geometry>
</collision>
</link>
<gazebo reference="some_link">
<collision name="some_link_collision">
<surface>
<friction>
<torsional>
<coefficient>0.456</coefficient>
<use_patch_radius>true</use_patch_radius>
<patch_radius>0.05</patch_radius>
</torsional>
</friction>
</surface>
</collision>
</gazebo>
</robot>
There's a tutorial on how to set up torsional friction in Gazebo here:
http://gazebosim.org/tutorials?tut=to...
Take a special note that this only works if you are using the ODE physics engine.
That explains how to set it up in SDF, not URDF. I believe that my problem is related to this, as I explained in detail here: https://answers.ros.org/question/271474/robot-slips-after-upgrade-to-kinetic/ Does anybody know how to fix this?
Asked: 2016-04-13 10:03:32 -0600
Seen: 4,204 times
Last updated: Oct 11 '17