choosing frictional parameters of a cube for sliding
I am trying to slide a cube using a robotic finger. I have a pre-computed joint-trajectory for the finger, that will execute a sliding motion once a contact is made is with the object. I expected the cube to slide when the motion is executed. However, I get a rolling kind of motion that prevent sliding, and the edge of cube seem to be sticky. Have I missed adding any parameters to the cube model? I use same value for mu and mu2 of the cube. Here is a gif of the simulation.
My observation:
mu, mu2: 0.7-0.75 --> cube slides very quickly as soon as contact is made (without requiring sliding motion)
mu, mu2: 0.76-0.79 --> cube slides quickly as soon as contact is made (without requiring sliding motion)
mu, mu2: > 0.8 --> cube tries to roll instead of sliding (with sliding motion (shown in the figure))
I saved the world after spawning the hand from xacro file. I removed some elements in the world file as they are repetitive for other fingers. The world file is:
<sdf version='1.6'>
<world name='default'>
<physics type="ode">
<gravity>0.000000 0.000000 -9.810000</gravity>
<ode>
<solver>
<type>quick</type>
<iters>100</iters>
<precon_iters>0</precon_iters>
<sor>1.000000</sor>
</solver>
<constraints>
<cfm>0.000000</cfm>
<erp>0.200000</erp>
<contact_max_correcting_vel>0.000000</contact_max_correcting_vel>
<contact_surface_layer>0.000000</contact_surface_layer>
</constraints>
</ode>
<real_time_update_rate>0.000000</real_time_update_rate>
<max_step_size>0.001000</max_step_size>
</physics>
<model name='r_shadow_motor_right'>
<link name='rh_ffdistal'>
<pose frame=''>0.033 -0.01 0.412 0 -0 0</pose>
<inertial>
<pose frame=''>0 0 0.013077 0 -0 0</pose>
<mass>0.013</mass>
<inertia>
<ixx>1.12092e-06</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1.28092e-06</iyy>
<iyz>0</iyz>
<izz>5.3e-07</izz>
</inertia>
</inertial>
<collision name='rh_ffdistal_collision'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>"package://sr_description/meshes/hand/ubi_tactiles/ubi_tip_collision.dae"</uri>
</mesh>
</geometry>
<surface>
<contact>
<ode>
<kp>1e+07</kp>
<kd>1</kd>
</ode>
</contact>
<friction>
<ode>
<mu>500</mu>
<mu2>500</mu2>
</ode>
<torsional>
<ode/>
</torsional>
</friction>
<bounce/>
</surface>
<max_contacts>10</max_contacts>
</collision>
<visual name='rh_ffdistal_visual'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>0.001 0.001 0.001</scale>
<uri>"package://sr_description/meshes/hand/ubi_tactiles/ubi_tip_visual.dae"</uri>
</mesh>
</geometry>
<material>
<script>
<uri>__default__</uri>
<name>__default__</name>
</script>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
<self_collide>1</self_collide>
</link>
</model>
</world>
</sdf>
cube model file is:
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="color_cube">
<xacro:property name="dx" value="0.06" /> <!-- length -->
<xacro:property name="dy" value="0.06" /> <!-- width -->
<xacro:property name="dz" value="0.06" /> <!-- height -->
<xacro:property name="mass" value="0.015" />
<gazebo reference="color_cube_link">
<xacro:property name="object_mu" default="0.78" />
<kp>10000000</kp>
<kd>1</kd>
<mu1>${object_mu}</mu1>
<mu2>${object_mu}</mu2>
<collision>
<geometry>
<box size="${dx} ${dy} ${dz}"/>
</geometry>
</collision>
</gazebo>
<link name="color_cube_link">
<inertial>
<mass value="${mass}" />
<origin xyz="0 0 0" />
<inertia ixx="${(mass/12.0) * (dy*dy + dz*dz)}" ixy="0.0" ixz="0.0"
iyx= "0.0" iyy="${(mass/12.0) * (dx*dx + dz*dz)}" iyz="0.0"
izx= "0.0" izy= "0.0" izz="${(mass/12.0) * (dx*dx + dy*dy)}" />
</inertial>
<visual>
<origin xyz="0 0 0"/>
<geometry>
<box size="${dx} ${dy} ${dz}"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0"/>
<geometry>
<box size="${dx} ${dy} ${dz}"/>
</geometry>
</collision>
</link>
<gazebo reference="color_cube_link">
<material>Gazebo/DarkYellow</material>
</gazebo>
</robot>
Asked by shameer on 2022-05-29 07:06:08 UTC
Comments