Gazebo | Ignition | Community
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

I've finally sorted it out. The problem was related to the missing <minDepth> tag.

Here is the working URDF portion:

        <gazebo reference="${name}_foot">
                <mu1>1</mu1>
                <mu2>1</mu2>
                <fdir1>1 0 0</fdir1>
                <maxContacts>1</maxContacts>
                <minDepth>0.005</minDepth>
                <gravity>true</gravity>
                <collision name="${name}_lowerleg_fixed_joint_lump__${name}_foot_collision_1">
                        <geometry>
                                <sphere>
                                        <!-- should be the same as surface_radius -->
                                        <radius>0.02175</radius>
                                </sphere>
                        </geometry>

                <surface>
                        <friction>
                                <torsional>
                                        <coefficient>10</coefficient>
                                        <use_patch_radius>false</use_patch_radius>
                                        <!-- should be the same as collision sphere radius -->
                                        <surface_radius>0.02175</surface_radius>
                                        <patch_radius>0.01</patch_radius>
                                </torsional>
                        </friction>
                        <contact>
                                <poissons_ratio>0.5</poissons_ratio>
                                <elastic_modulus>1e8</elastic_modulus>
                        </contact>
                </surface>
        </collision>

        <material>Gazebo/Black</material>
        </gazebo>