The robot tool is a prismatic gripper with four rods that slip into matching holes on the object to be grasped. Using this gripper to move the object works fine for motion perpendicular to the rod axes. In the video, for example, the rods are parallel to the world x-axis so motion in the z-y plane is fine; the robot lifts the object then translates in the negative y-direction okay. I think the problem is that the friction force is not being computed well because when the robot translates in the x-direction the object seems to stay put until it reaches the end of the rod and then it goes berserk. (If you look closely in the second video it can be seen that the gripper starts to move to the right and the object stays still. I guess the object crosses the camera in that video so we get to see the holes and rods inside the object.)
There is a second reason I think the friction calculation is to blame: a different pick-and-place simulation I made this year had problems lifting objects via friction. See Question 1, Question 2, and Question 3.
So far I've tried modifying physics tags in the world file, as well as collision surface tags in both the object sdf and the gripper urdf. It's apparent that changing these files has some effect (though mu1 and mu2 don't make any difference) but the problem persists. The files are pasted below.
It also seems to me that this could be a problem to do with Gazebo 9, which is what I moved to because the previous project had a mobile base that could not move due to this bug with Gazebo 7 and ros_control. Since this simulation does not have a mobile base I will try reverting to Gazebo 7 to see if that fixes the gripping problem.
One other tidbit: if the mass of the object is too high (though still less than 1) it will fall during the upward motion. So that's fun :-/
World file:
<sdf version='1.5'>
<world name='default'>
<!-- A global light source -->
<include>
<uri>model://sun</uri>
</include>
<!-- A ground plane -->
<include>
<uri>model://ground_plane</uri>
</include>
<!-- Set physics parameters to hopefully improve contact behavior -->
<!-- Default max_step_size is 0.001 -->
<!-- Product of r_t_u_r and m_s_s gives target realTimeFactor, I think. Default is 1000. -->
<!-- Default iters is 50 -->
<physics type="ode">
<max_step_size>0.0005</max_step_size>
<real_time_update_rate>2000</real_time_update_rate>
<ode>
<solver>
<iters>100</iters>
</solver>
</ode>
</physics>
</world>
</sdf>
Object sdf:
<sdf version='1.6'>
<model name='object'>
<link name='object'>
<pose frame=''>0 0 0 0 0 0</pose>
<inertial>
<pose frame=''>0 0.00594 0.31407 0 0 0</pose>
<mass>0.01</mass>
<inertia>
<ixx>0.01</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.01</iyy>
<iyz>0</iyz>
<izz>0.01</izz>
</inertia>
</inertial>
<collision name=object_collision'>
<surface>
<contact>
<ode>
<max_vel>0</max_vel>
<min_depth>0.0001</min_depth>
<!--
<kp>1e8</kp>
<kd>1e0</kd>-->
</ode>
</contact>
<friction>
<ode>
<mu>1000000.0</mu>
<mu2>1000000.0</mu2>
</ode>
</friction>
</surface>
<pose frame=''>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>0.0254 0.0254 0.0254</scale>
<uri>model://object/meshes/object.stl</uri>
</mesh>
</geometry>
</collision>
<visual name='object_visual'>
<pose frame=''>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<scale>0.0254 0.0254 0.0254</scale>
<uri>model://object/meshes/object.stl</uri>
</mesh>
</geometry>
</visual>
</link>
</model>
</sdf>
Gripper urdf:
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from gripper_placer.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="gripper_placer" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- Default is 0.01 -->
<!-- 0.0393701 -->
<!-- Phantom link for center of gripper -->
<link name="gripper_center">
<inertial>
<mass value="0.01"/>
<inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001"/>
</inertial>
</link>
<!-- One side of gripper -->
<link name="side_p">
<visual>
<origin rpy="0 0 0" xyz="0 0 0.11485"/>
<geometry>
<mesh filename="package://hydra/models/gripper_placer/meshes/gripper_pad_v2.stl" scale="0.0254 0.0254 0.0254"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.11485"/>
<geometry>
<mesh filename="package://hydra/models/gripper_placer/meshes/gripper_pad_v2.stl" scale="0.0254 0.0254 0.0254"/>
</geometry>
</collision>
<inertial>
<mass value="0.001"/>
<inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.02" iyz="0.0" izz="0.02"/>
</inertial>
</link>
<!-- Second side of gripper -->
<link name="side_d">
<visual>
<origin rpy="0 0 3.14159265359" xyz="0 0 0.11485"/>
<!--origin xyz="0 0.04185 0" rpy="0 0 ${pi}" /-->
<geometry>
<mesh filename="package://hydra/models/gripper_placer/meshes/gripper_pad_v2.stl" scale="0.0254 0.0254 0.0254"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 3.14159265359" xyz="0 0 0.11485"/>
<geometry>
<mesh filename="package://hydra/models/gripper_placer/meshes/gripper_pad_v2.stl" scale="0.0254 0.0254 0.0254"/>
</geometry>
</collision>
<inertial>
<mass value="0.001"/>
<inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.02" iyz="0.0" izz="0.02"/>
</inertial>
</link>
<!-- Prismatic joint -->
<joint name="gripper_joint_p" type="prismatic">
<origin rpy="0 0 0" xyz="0 0 0"/>
<axis xyz="0 1 0"/>
<parent link="gripper_center"/>
<child link="side_p"/>
<limit effort="5000" lower="-100" upper="100" velocity="0.5"/>
</joint>
<joint name="gripper_joint_d" type="prismatic">
<origin rpy="0 0 0" xyz="0 0 0"/>
<axis xyz="0 1 0"/>
<parent link="gripper_center"/>
<child link="side_d"/>
<limit effort="5000" lower="-100" upper="100" velocity="0.5"/>
</joint>
<transmission name="gripper_joint_transmission_p">
<type>transmission_interface/SimpleTransmission</type>
<joint name="gripper_joint_p">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="gripper_joint_motor_p">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="gripper_joint_transmission_d">
<type>transmission_interface/SimpleTransmission</type>
<joint name="gripper_joint_d">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="gripper_joint_motor_d">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- Gazebo tag for hopefully changing physics engine properties to work -->
<gazebo>
<maxVel>0</maxVel>
<minDepth>0.001</minDepth>
</gazebo>
</robot>