Add damping and friction parameters (URDF).
authorGabriel Schmitz <gschmitz@ece.ufrgs.br>
Wed, 20 Feb 2019 18:38:45 +0000 (15:38 -0300)
committerGabriel Schmitz <gschmitz@ece.ufrgs.br>
Wed, 20 Feb 2019 18:38:45 +0000 (15:38 -0300)
miitzhand_description/urdf/miitzhand.urdf

index d019747..007ce6f 100644 (file)
@@ -78,7 +78,8 @@
     <parent link="little_l0" />
     <child link="little_l1" />
     <axis xyz="0 0 1" />
-    <limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />
+    <limit lower="-1.57" upper="0" effort="1.968989" velocity="5.61" />
+    <dynamics damping="0.336538" friction="0.075478" />
   </joint>
 
  <link name="little_l2">
     <parent link="little_l1" />
     <child link="little_l2" />
     <axis xyz="0 0 1" />
-    <limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />    
+    <limit lower="-1.57" upper="0" effort="1.968989" velocity="5.61" />
+    <dynamics damping="0.336538" friction="0.075478" />    
     <mimic joint="little_j1" multiplier="1" offset="0" />
   </joint>
 
     <parent link="little_l2" />
     <child link="little_l3" />
     <axis xyz="0 0 1" />
-    <limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />    
+    <limit lower="-1.57" upper="0" effort="1.968989" velocity="5.61" />    
     <mimic joint="little_j1" multiplier="1" offset="0" />
   </joint>
 
     <parent link="ring_l0" />
     <child link="ring_l1" />
     <axis xyz="0 0 1" />
-    <limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />
+    <limit lower="-1.57" upper="0" effort="1.968989" velocity="5.61" />
+    <dynamics damping="0.336538" friction="0.075478" />
   </joint>
 
  <link name="ring_l2">
     <parent link="ring_l1" />
     <child link="ring_l2" />
     <axis xyz="0 0 1" />
-    <limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />    
+    <limit lower="-1.57" upper="0" effort="1.968989" velocity="5.61" />    
     <mimic joint="ring_j1" multiplier="1" offset="0" />
   </joint>
 
     <parent link="ring_l2" />
     <child link="ring_l3" />
     <axis xyz="0 0 1" />
-    <limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />
+    <limit lower="-1.57" upper="0" effort="1.968989" velocity="5.61" />
     <mimic joint="ring_j1" multiplier="1" offset="0" />
   </joint>
 
     <parent link="middle_l0" />
     <child link="middle_l1" />
     <axis xyz="0 0 1" />
-    <limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />
+    <limit lower="-1.57" upper="0" effort="1.968989" velocity="5.61" />
+    <dynamics damping="0.336538" friction="0.075478" />
   </joint>
 
   <link name="middle_l2">
     <parent link="middle_l1" />
     <child link="middle_l2" />
     <axis xyz="0 0 1" />
-    <limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />    
+    <limit lower="-1.57" upper="0" effort="1.968989" velocity="5.61" />    
     <mimic joint="middle_j1" multiplier="1" offset="0" />
   </joint>
 
     <parent link="middle_l2" />
     <child link="middle_l3" />
     <axis xyz="0 0 1" />
-    <limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />    
+    <limit lower="-1.57" upper="0" effort="1.968989" velocity="5.61" />    
     <mimic joint="middle_j1" multiplier="1" offset="0" />
   </joint>
 
     <parent link="index_l0" />
     <child link="index_l1" />
     <axis xyz="0 0 1" />
-    <limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" /> 
+    <limit lower="-1.57" upper="0" effort="1.968989" velocity="5.61" /> 
+    <dynamics damping="0.336538" friction="0.075478" />
   </joint>
 
  <link name="index_l2">
     <parent link="index_l1" />
     <child link="index_l2" />
     <axis xyz="0 0 1" />
-    <limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />    
+    <limit lower="-1.57" upper="0" effort="1.968989" velocity="5.61" />    
     <mimic joint="index_j1" multiplier="1" offset="0" />
   </joint>
 
     <parent link="index_l2" />
     <child link="index_l3" />
     <axis xyz="0 0 1" />
-    <limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />    
+    <limit lower="-1.57" upper="0" effort="1.968989" velocity="5.61" />    
     <mimic joint="index_j1" multiplier="1" offset="0" />
   </joint>
 
     <parent link="thumb_l0" />
     <child link="thumb_l1" />
     <axis xyz="0 0 1" />
-    <limit lower="0" upper="1.57" effort="0.37" velocity="5.61" />
+    <limit lower="0" upper="1.57" effort="1.968989" velocity="5.61" />
+    <dynamics damping="0.336538" friction="0.075478" />
   </joint>
 
   <link name="thumb_l2">
     <parent link="thumb_l1" />
     <child link="thumb_l2" />
     <axis xyz="0 0 1" />
-    <limit lower="-3.14" upper="-1.57" effort="0.37" velocity="5.61" />
+    <limit lower="-3.14" upper="-1.57" effort="1.968989" velocity="5.61" />
+    <dynamics damping="0.336538" friction="0.075478" />
   </joint>
 
  <link name="thumb_l3">
     <parent link="thumb_l2" />
     <child link="thumb_l3" />
     <axis xyz="0 0 1" />
-    <limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />    
+    <limit lower="-1.57" upper="0" effort="1.968989" velocity="5.61" />    
     <mimic joint="thumb_j2" multiplier="1" offset="1.57" />
   </joint>