Fix origin of joint ring_j0.
authorWalter Fetter Lages <w.fetter@ieee.org>
Sat, 13 Apr 2019 23:03:13 +0000 (20:03 -0300)
committerWalter Fetter Lages <w.fetter@ieee.org>
Sat, 13 Apr 2019 23:03:13 +0000 (20:03 -0300)
miitzhand_description/urdf/miitzhand.urdf

index 4a10bec..6db83f6 100644 (file)
  <joint name="ring_j0" type="fixed">
    <parent link="base_link"/>
    <child link="ring_l0"/>
-   <origin xyz="0.12886 0.003 -0.017716" rpy="0.167747119817 0.034907 0" />
+   <origin xyz="0.12886 0 -0.017716" rpy="0 0 1.5708" />
  </joint>
 
  <link name="ring_l1">
  </link>
 
   <joint name="ring_j1" type="revolute">
-    <origin xyz="0 0 0" rpy="-0.167747119817 0 0" />
+    <origin xyz="0.003 0 0" rpy="0.034907 0 0" />
     <parent link="ring_l0" />
     <child link="ring_l1" />
     <axis xyz="0 0 1" />
-    <limit lower="-1.57" upper="0" effort="1.968989" velocity="5.61" />
+    <limit lower="-3.14" upper="-1.57" effort="1.968989" velocity="5.61" />
     <dynamics damping="0.336538" friction="0.075478" />
   </joint>
 
     <child link="ring_l2" />
     <axis xyz="0 0 1" />
     <limit lower="-1.57" upper="0" effort="1.968989" velocity="5.61" />    
-    <mimic joint="ring_j1" multiplier="1" offset="0" />
+    <mimic joint="ring_j1" multiplier="1" offset="1.57" />
   </joint>
 
  <link name="ring_l3">
     <child link="ring_l3" />
     <axis xyz="0 0 1" />
     <limit lower="-1.57" upper="0" effort="1.968989" velocity="5.61" />
-    <mimic joint="ring_j1" multiplier="1" offset="0" />
+    <mimic joint="ring_j1" multiplier="1" offset="1.57" />
   </joint>
 
  <link name="middle_l0"/>