Picking up a soft ball using dual arm
I am trying to pick a soft ball using two arms and then throw it. I am using a soft ball because I want to be able to throw the ball even when it is slightly crushed by the fingers.
But when I try to run it using gazebo, the ball jumps around on contact. I tried making the object soft using different values of kp, kd, soft_cfm and soft_erp
with no success. Any suggestions on how I can achieve this.
ball.sdf
<model name="basketball">
<static>false</static>
<link name="ball">
<inertial>
<mass>0.25</mass>
<!-- inertia based on solid sphere 2/5 mr^2 -->
<inertia>
<ixx>0.00169</ixx>
<iyy>0.00169</iyy>
<izz>0.00169</izz>
<ixy>0</ixy>
<ixz>0</ixz>
<iyz>0</iyz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<sphere>
<!-- <radius>0.1172</radius> -->
<radius>0.13</radius>
</sphere>
</geometry>
</visual>
<collision name="collision">
<geometry>
<sphere>
<radius>0.13</radius>
</sphere>
</geometry>
</collision>
</link>
</model>
finger.sdf
<model name="finger">
<joint name="asdf" type="fixed">
<parent link="world"/>
<child link="finger_link"/>
<pose frame="">0 0 0 0 1.5707963267948966 0</pose>
</joint>
<link name="finger_link">
<visual name='visual'>
<pose frame="">0 0 0 1.5707963267948966 0 0</pose>
<geometry>
<mesh><uri>model://finger/finger.stl</uri></mesh>
</geometry>
<material name="white"/>
</visual>
<inertial>
<pose frame="">0 0 0 0 0 0</pose>
<mass value="0.250"/>
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0"/>
</inertial>
</link>
</model>
Just before the contact between the fingers and the ball
Collision model
Without diving in deeper into dynamics, I noticed that finger inertias have zero MOI, this is a specialized case that we have not explored much in gazebo. Can you assign realistic finger inertia complete with finite MOI?
please provide example complete with kp, kd, soft_cfm and soft_erp.
@hsu I modeled the fingers as a box and set the inertia of the diagonal to `Ixx=0.0008125 Iyy=Izz=0.001125`. But that did not help. I am not sure about the cfm and kp values. I used random set of values. Few that I tried are `kd=1, kp=1000, cfm=erp=1`. But then the ball goes through the cylinder.
@hsu Do you have any thoughts on how I could accomplish this.. thanks