Change parent of joints *_j1 to base_link. Gazebo have problems with a parent link...
authorWalter Fetter Lages <w.fetter@ieee.org>
Sat, 4 May 2019 20:53:53 +0000 (17:53 -0300)
committerWalter Fetter Lages <w.fetter@ieee.org>
Sat, 4 May 2019 20:53:53 +0000 (17:53 -0300)
miitzhand_description/urdf/miitzhand.urdf

index 0bf5e88..03d030a 100644 (file)
     </collision>
  </link>
 
+  <!-- 
+       It appears that Gazebo do not recognize joints in which the parent
+       link does not have inertial properties. Hence attach litte_l1
+       directly to base_link and not to little_l0.
+  -->
   <joint name="little_j1" type="revolute">
-    <origin xyz="-0.0015817 0 0" rpy="0.087267 0 0" />
-    <parent link="little_l0" />
+    <origin xyz="0.11977 -0.003 -0.04062" rpy="-0.034907 0.087266 1.5708" />
+    <parent link="base_link" />
     <child link="little_l1" />
     <axis xyz="0 0 1" />
     <limit lower="-3.14" upper="-1.57" effort="1.968989" velocity="5.61" />
     </collision>
  </link>
 
+  <!-- 
+       It appears that Gazebo do not recognize joints in which the parent
+       link does not have inertial properties. Hence attach ring_l1
+       directly to base_link and not to ring_l0.
+  -->
   <joint name="ring_j1" type="revolute">
-    <origin xyz="0.003 0 0" rpy="0.034907 0 0" />
-    <parent link="ring_l0" />
+    <origin xyz="0.12886 0.003 -0.017716" rpy="0 0.034907 1.5807" />
+    <parent link="base_link" />
     <child link="ring_l1" />
     <axis xyz="0 0 1" />
     <limit lower="-3.14" upper="-1.57" effort="1.968989" velocity="5.61" />
     </collision>
  </link>
 
+  <!-- 
+       It appears that Gazebo do not recognize joints in which the parent
+       link does not have inertial properties. Hence attach middle_l1
+       directly to base_link and not to middle_l0.
+  -->
   <joint name="middle_j1" type="revolute">
-    <origin xyz="0.0032071 0 0" rpy="0 0 0" />
-    <parent link="middle_l0" />
+    <origin xyz="0.1285 0.003 0.007" rpy="0.061087 0 1.5708" />
+    <parent link="base_link" />
     <child link="middle_l1" />
     <axis xyz="0 0 1" />
     <limit lower="-3.14" upper="-1.57" effort="1.968989" velocity="5.61" />
     </collision>
  </link>
 
+  <!-- 
+       It appears that Gazebo do not recognize joints in which the parent
+       link does not have inertial properties. Hence attach index_l1
+       directly to base_link and not to index_l0.
+  -->
   <joint name="index_j1" type="revolute">
-    <origin xyz="0.0030963 0 0" rpy="0 0 0" />
-    <parent link="index_l0" />
+    <origin xyz="0.12828 0 0.030847" rpy="0.10123 -0.017453 1.5708" />
+    <parent link="base_link" />
     <child link="index_l1" />
     <axis xyz="0 0 1" />
     <limit lower="-3.14" upper="-1.57" effort="1.968989" velocity="5.61" />
     </collision>
  </link>
 
+  <!-- 
+       It appears that Gazebo do not recognize joints in which the parent
+       link does not have inertial properties. Hence attach thumb_l1
+       directly to base_link and not to thumb_l0.
+  -->
   <joint name="thumb_j1" type="revolute">
-    <origin xyz="0.00034464 0 0" rpy="0.87266 0 0" />
-    <parent link="thumb_l0" />
+    <origin xyz="0.070929 0.00034464 0.043575" rpy="0.87266 0 1.5708" />
+    <parent link="base_link" />
     <child link="thumb_l1" />
     <axis xyz="0 0 1" />
     <limit lower="0" upper="1.57" effort="1.968989" velocity="5.61" />
 <transmission name="thumb1_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="thumb_j1">    
-                <hardwareInterface>EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
         </joint>    
         <actuator name="thumb1_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
 <transmission name="thumb2_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="thumb_j2">    
-                <hardwareInterface>EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
         </joint>    
         <actuator name="thumb2_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
 <transmission name="thumb3_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="thumb_j3">    
-                <hardwareInterface>EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
         </joint>    
         <actuator name="thumb3_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
 <transmission name="index1_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="index_j1">    
-                <hardwareInterface>EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
         </joint>    
         <actuator name="index1_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
 <transmission name="index2_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="index_j2">    
-                <hardwareInterface>EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
         </joint>    
         <actuator name="index2_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
 <transmission name="index3_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="index_j3">    
-                <hardwareInterface>EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
         </joint>    
         <actuator name="index3_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
 <transmission name="middle1_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="middle_j1">    
-                <hardwareInterface>EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
         </joint>    
         <actuator name="middle1_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
 <transmission name="middle2_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="middle_j2">    
-                <hardwareInterface>EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
         </joint>    
         <actuator name="middle2_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
 <transmission name="middle3_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="middle_j3">    
-                <hardwareInterface>EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
         </joint>    
         <actuator name="middle3_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
 <transmission name="ring1_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="ring_j1">    
-                <hardwareInterface>EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
         </joint>    
         <actuator name="ring1_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
 <transmission name="ring2_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="ring_j2">    
-                <hardwareInterface>EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
         </joint>    
         <actuator name="ring2_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
 <transmission name="ring3_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="ring_j3">    
-                <hardwareInterface>EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
         </joint>    
         <actuator name="ring3_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
 <transmission name="little1_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="little_j1">    
-                <hardwareInterface>EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
         </joint>    
         <actuator name="little1_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
 <transmission name="little2_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="little_j2">    
-                <hardwareInterface>EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
         </joint>    
         <actuator name="little2_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>    
 <transmission name="little3_transmission">    
         <type>transmission_interface/SimpleTransmission</type>    
         <joint name="little_j3">    
-                <hardwareInterface>EffortJointInterface</hardwareInterface>    
+                <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>    
         </joint>    
         <actuator name="little3_motor">    
                 <mechanicalReduction>1.87</mechanicalReduction>