-<robot name="miitzhand">
+<robot name="miitzhand">
+
+ <link name="world"/>
- <link name="world"/>
-
- <link name="origin_link"/>
- <joint name="origin_joint" type="fixed" >
- <parent link="world"/>
- <child link="origin_link"/>
- </joint>
-
- <link name="base_link">
- <inertial>
- <origin xyz="-0.00037433 0.0019683 0.070254" rpy="0 0 0" />
- <mass value="0.16419" />
- <inertia ixx="0.00024692" ixy="-3.8095E-06" ixz="1.5276E-06" iyy="0.00015647" iyz="-1.4218E-06" izz="0.00010717" />
- </inertial>
-
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/base_link.stl" />
- </geometry>
- <material name="">
- <color rgba="1 1 1 1" />
- </material>
- </visual>
-
- <collision>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/base_link.stl" />
- </geometry>
- </collision>
- </link>
-
- <joint name="base_joint" type="fixed" >
+ <link name="origin_link"/>
+
+ <joint name="origin_joint" type="fixed" >
+ <parent link="world"/>
+ <child link="origin_link"/>
+ </joint>
+
+ <link name="base_link">
+ <inertial>
+ <origin xyz="0.070254 0.00037433 -0.0019683" rpy="0 0 0" />
+ <mass value="0.16419" />
+ <inertia ixx="0.00010717" ixy="-1.5276E-06" ixz="1.4218E-06" iyy="0.00024692" iyz="-3.8095E-06" izz="0.00015647" />
+ </inertial>
+
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/base_link.stl" />
+ </geometry>
+ <material name="">
+ <color rgba="1 1 1 1" />
+ </material>
+ </visual>
+
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/base_link.stl" />
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="base_joint" type="fixed" >
+ <origin xyz="0 0 0" rpy="0 -1.5708 0" />
<parent link="origin_link"/>
<child link="base_link"/>
- </joint>
-
- <link name="little_l1">
- <inertial>
- <origin xyz="0.021926 0.00020302 9.6353E-08" rpy="0 0 0" />
- <mass value="0.010346" />
- <inertia ixx="4.6802E-07" ixy="5.726E-08" ixz="1.4761E-11" iyy="2.4622E-06" iyz="4.7237E-11" izz="2.4327E-06" />
- </inertial>
-
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/little_l1.stl" />
- </geometry>
- <material name="">
- <color rgba="1 1 1 1" />
- </material>
- </visual>
-
- <collision>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/little_l1.stl" />
- </geometry>
- </collision>
- </link>
-
- <joint name="little_j1" type="revolute">
- <origin xyz="0.003 0.04062 0.11977" rpy="-0.034907 -1.4835 1.5708" />
- <parent link="base_link" />
- <child link="little_l1" />
- <axis xyz="0 0 1" />
- <limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />
- </joint>
-
- <link name="little_l2">
- <inertial>
- <origin xyz="0.010872 0.00039672 4.7668E-06" rpy="0 0 0" />
- <mass value="0.0052657" />
- <inertia ixx="2.3451E-07" ixy="2.5431E-08" ixz="-2.1744E-11" iyy="6.3027E-07" iyz="2.6048E-10" izz="6.1275E-07" />
- </inertial>
-
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/little_l2.stl" />
- </geometry>
- <material name="">
- <color rgba="1 1 1 1" />
- </material>
- </visual>
-
- <collision>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/little_l2.stl" />
- </geometry>
- </collision>
- </link>
-
- <joint name="little_j2" type="revolute">
- <origin xyz="0.047 0 0" rpy="0 0 0" />
- <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" />
- <mimic joint="little_j1" multiplier="1" offset="0" />
</joint>
-
- <link name="little_l3">
- <inertial>
- <origin xyz="0.0099715 0.00045399 -2.4744E-07" rpy="0 0 0" />
- <mass value="0.0049969" />
- <inertia ixx="1.7179E-07" ixy="2.5186E-08" ixz="7.6349E-12" iyy="4.632E-07" iyz="-6.3855E-11" izz="4.9237E-07" />
- </inertial>
-
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/little_l3.stl" />
- </geometry>
- <material name="">
- <color rgba="1 1 1 1" />
- </material>
+
+ <link name="little_l1">
+ <inertial>
+ <origin xyz="0.021926 0.00020302 9.6353E-08" rpy="0 0 0" />
+ <mass value="0.010346" />
+ <inertia ixx="4.6802E-07" ixy="5.726E-08" ixz="1.4761E-11" iyy="2.4622E-06" iyz="4.7237E-11" izz="2.4327E-06" />
+ </inertial>
+
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/little_l1.stl" />
+ </geometry>
+ <material name="">
+ <color rgba="1 1 1 1" />
+ </material>
+ </visual>
+
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/little_l1.stl" />
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="little_j1" type="revolute">
+ <origin xyz="0.11977 -0.003 -0.04062" rpy="-0.034907 0.087266 0" />
+ <parent link="base_link" />
+ <child link="little_l1" />
+ <axis xyz="0 0 1" />
+ <limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />
+ </joint>
+
+ <link name="little_l2">
+ <inertial>
+ <origin xyz="0.010872 0.00039672 4.7668E-06" rpy="0 0 0" />
+ <mass value="0.0052657" />
+ <inertia ixx="2.3451E-07" ixy="2.5431E-08" ixz="-2.1744E-11" iyy="6.3027E-07" iyz="2.6048E-10" izz="6.1275E-07" />
+ </inertial>
+
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/little_l2.stl" />
+ </geometry>
+ <material name="">
+ <color rgba="1 1 1 1" />
+ </material>
</visual>
-
- <collision>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/little_l3.stl" />
- </geometry>
- </collision>
- </link>
-
- <joint name="little_j3" type="revolute">
- <origin xyz="0.0267 0 0" rpy="0 0 0" />
- <parent link="little_l2" />
- <child link="little_l3" />
- <axis xyz="0 0 1" />
+
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/little_l2.stl" />
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="little_j2" type="revolute">
+ <origin xyz="0.047 0 0" rpy="0 0 0" />
+ <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" />
- <mimic joint="little_j1" multiplier="1" offset="0" />
- </joint>
-
- <link name="ring_l1">
- <inertial>
- <origin xyz="0.021926 0.00020302 9.349E-08" rpy="0 0 0" />
- <mass value="0.010346" />
- <inertia ixx="4.6802E-07" ixy="5.726E-08" ixz="1.4301E-11" iyy="2.4622E-06" iyz="4.7323E-11" izz="2.4327E-06" />
+ <mimic joint="little_j1" multiplier="1" offset="0" />
+ </joint>
+
+ <link name="little_l3">
+ <inertial>
+ <origin xyz="0.0099715 0.00045399 -2.4744E-07" rpy="0 0 0" />
+ <mass value="0.0049969" />
+ <inertia ixx="1.7179E-07" ixy="2.5186E-08" ixz="7.6349E-12" iyy="4.632E-07" iyz="-6.3855E-11" izz="4.9237E-07" />
</inertial>
-
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/ring_l1.stl" />
- </geometry>
- <material name="">
- <color rgba="1 1 1 1" />
- </material>
- </visual>
-
- <collision>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/ring_l1.stl" />
- </geometry>
- </collision>
- </link>
-
- <joint name="ring_j1" type="revolute">
- <origin xyz="-0.003 0.017716 0.12886" rpy="0 -1.5359 1.5708" />
- <parent link="base_link" />
- <child link="ring_l1" />
- <axis xyz="0 0 1" />
- <limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />
- </joint>
-
- <link name="ring_l2">
- <inertial>
- <origin xyz="0.010872 0.00039795 1.1259E-06" rpy="0 0 0" />
- <mass value="0.0052659" />
- <inertia ixx="2.3451E-07" ixy="2.5367E-08" ixz="4.1433E-11" iyy="6.303E-07" iyz="1.167E-10" izz="6.1276E-07" />
- </inertial>
-
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/ring_l2.stl" />
- </geometry>
- <material name="">
- <color rgba="1 1 1 1" />
- </material>
- </visual>
-
- <collision>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/ring_l2.stl" />
- </geometry>
- </collision>
- </link>
-
- <joint name="ring_j2" type="revolute">
- <origin xyz="0.047 0 0" rpy="0 0 0" />
- <parent link="ring_l1" />
- <child link="ring_l2" />
- <axis xyz="0 0 1" />
+
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/little_l3.stl" />
+ </geometry>
+ <material name="">
+ <color rgba="1 1 1 1" />
+ </material>
+ </visual>
+
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/little_l3.stl" />
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="little_j3" type="revolute">
+ <origin xyz="0.0267 0 0" rpy="0 0 0" />
+ <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" />
- <mimic joint="ring_j1" multiplier="1" offset="0" />
+ <mimic joint="little_j1" multiplier="1" offset="0" />
+ </joint>
+
+ <link name="ring_l1">
+ <inertial>
+ <origin xyz="0.021926 0.00020302 9.349E-08" rpy="0 0 0" />
+ <mass value="0.010346" />
+ <inertia ixx="4.6802E-07" ixy="5.726E-08" ixz="1.4301E-11" iyy="2.4622E-06" iyz="4.7323E-11" izz="2.4327E-06" />
+ </inertial>
+
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/ring_l1.stl" />
+ </geometry>
+ <material name="">
+ <color rgba="1 1 1 1" />
+ </material>
+ </visual>
+
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/ring_l1.stl" />
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="ring_j1" type="revolute">
+ <origin xyz="0.12886 0.003 -0.017716" rpy="0 0.034907 0" />
+ <parent link="base_link" />
+ <child link="ring_l1" />
+ <axis xyz="0 0 1" />
+ <limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />
</joint>
-
- <link name="ring_l3">
- <inertial>
- <origin xyz="0.0099715 0.00045398 -2.4944E-07" rpy="0 0 0" />
- <mass value="0.0049969" />
- <inertia ixx="1.7179E-07" ixy="2.5186E-08" ixz="7.604E-12" iyy="4.632E-07" iyz="-6.3764E-11" izz="4.9237E-07" />
- </inertial>
-
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/ring_l3.stl" />
- </geometry>
- <material name="">
- <color rgba="1 1 1 1" />
- </material>
- </visual>
-
- <collision>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/ring_l3.stl" />
- </geometry>
- </collision>
- </link>
-
- <joint name="ring_j3" type="revolute">
- <origin xyz="0.0267 0 0" rpy="0 0 0" />
- <parent link="ring_l2" />
- <child link="ring_l3" />
- <axis xyz="0 0 1" />
+
+ <link name="ring_l2">
+ <inertial>
+ <origin xyz="0.010872 0.00039795 1.1259E-06" rpy="0 0 0" />
+ <mass value="0.0052659" />
+ <inertia ixx="2.3451E-07" ixy="2.5367E-08" ixz="4.1433E-11" iyy="6.303E-07" iyz="1.167E-10" izz="6.1276E-07" />
+ </inertial>
+
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/ring_l2.stl" />
+ </geometry>
+ <material name="">
+ <color rgba="1 1 1 1" />
+ </material>
+ </visual>
+
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/ring_l2.stl" />
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="ring_j2" type="revolute">
+ <origin xyz="0.047 0 0" rpy="0 0 0" />
+ <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" />
- <mimic joint="ring_j1" multiplier="1" offset="0" />
- </joint>
-
- <link name="middle_l1">
- <inertial>
- <origin xyz="0.021926 0.00020303 9.1214E-08" rpy="0 0 0" />
- <mass value="0.010346" />
- <inertia ixx="4.6802E-07" ixy="5.7259E-08" ixz="1.3936E-11" iyy="2.4622E-06" iyz="4.7436E-11" izz="2.4327E-06" />
+ <mimic joint="ring_j1" multiplier="1" offset="0" />
+ </joint>
+
+ <link name="ring_l3">
+ <inertial>
+ <origin xyz="0.0099715 0.00045398 -2.4944E-07" rpy="0 0 0" />
+ <mass value="0.0049969" />
+ <inertia ixx="1.7179E-07" ixy="2.5186E-08" ixz="7.604E-12" iyy="4.632E-07" iyz="-6.3764E-11" izz="4.9237E-07" />
</inertial>
-
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/middle_l1.stl" />
- </geometry>
- <material name="">
- <color rgba="1 1 1 1" />
- </material>
+
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/ring_l3.stl" />
+ </geometry>
+ <material name="">
+ <color rgba="1 1 1 1" />
+ </material>
</visual>
-
- <collision>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/middle_l1.stl" />
- </geometry>
- </collision>
- </link>
-
- <joint name="middle_j1" type="revolute">
- <origin xyz="-0.003 -0.007 0.1285" rpy="1.5097 -1.5708 0" />
- <parent link="base_link" />
- <child link="middle_l1" />
- <axis xyz="0 0 1" />
- <limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />
+
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/ring_l3.stl" />
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="ring_j3" type="revolute">
+ <origin xyz="0.0267 0 0" rpy="0 0 0" />
+ <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" />
+ <mimic joint="ring_j1" multiplier="1" offset="0" />
+ </joint>
+
+ <link name="middle_l1">
+ <inertial>
+ <origin xyz="0.021926 0.00020303 9.1214E-08" rpy="0 0 0" />
+ <mass value="0.010346" />
+ <inertia ixx="4.6802E-07" ixy="5.7259E-08" ixz="1.3936E-11" iyy="2.4622E-06" iyz="4.7436E-11" izz="2.4327E-06" />
+ </inertial>
+
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/middle_l1.stl" />
+ </geometry>
+ <material name="">
+ <color rgba="1 1 1 1" />
+ </material>
+ </visual>
+
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/middle_l1.stl" />
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="middle_j1" type="revolute">
+ <origin xyz="0.1285 0.003 0.007" rpy="0.061087 0 0" />
+ <parent link="base_link" />
+ <child link="middle_l1" />
+ <axis xyz="0 0 1" />
+ <limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />
</joint>
-
- <link name="middle_l2">
- <inertial>
- <origin xyz="0.010872 0.00039802 1.0929E-06" rpy="0 0 0" />
- <mass value="0.0052658" />
- <inertia ixx="2.345E-07" ixy="2.5369E-08" ixz="4.0562E-11" iyy="6.303E-07" iyz="1.133E-10" izz="6.1276E-07" />
+
+ <link name="middle_l2">
+ <inertial>
+ <origin xyz="0.010872 0.00039802 1.0929E-06" rpy="0 0 0" />
+ <mass value="0.0052658" />
+ <inertia ixx="2.345E-07" ixy="2.5369E-08" ixz="4.0562E-11" iyy="6.303E-07" iyz="1.133E-10" izz="6.1276E-07" />
</inertial>
-
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/middle_l2.stl" />
- </geometry>
- <material name="">
- <color rgba="1 1 1 1" />
- </material>
+
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/middle_l2.stl" />
+ </geometry>
+ <material name="">
+ <color rgba="1 1 1 1" />
+ </material>
</visual>
-
- <collision>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/middle_l2.stl" />
- </geometry>
- </collision>
- </link>
-
- <joint name="middle_j2" type="revolute">
- <origin xyz="0.047 0 0" rpy="0 0 0" />
- <parent link="middle_l1" />
- <child link="middle_l2" />
- <axis xyz="0 0 1" />
+
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/middle_l2.stl" />
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="middle_j2" type="revolute">
+ <origin xyz="0.047 0 0" rpy="0 0 0" />
+ <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" />
- <mimic joint="middle_j1" multiplier="1" offset="0" />
+ <mimic joint="middle_j1" multiplier="1" offset="0" />
</joint>
-
- <link name="middle_l3">
- <inertial>
- <origin xyz="0.0099715 0.00045399 -2.4729E-07" rpy="0 0 0" />
- <mass value="0.0049969" />
- <inertia ixx="1.7179E-07" ixy="2.5186E-08" ixz="7.5922E-12" iyy="4.632E-07" iyz="-6.3732E-11" izz="4.9237E-07" />
- </inertial>
-
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/middle_l3.stl" />
- </geometry>
- <material name="">
- <color rgba="1 1 1 1" />
- </material>
+
+ <link name="middle_l3">
+ <inertial>
+ <origin xyz="0.0099715 0.00045399 -2.4729E-07" rpy="0 0 0" />
+ <mass value="0.0049969" />
+ <inertia ixx="1.7179E-07" ixy="2.5186E-08" ixz="7.5922E-12" iyy="4.632E-07" iyz="-6.3732E-11" izz="4.9237E-07" />
+ </inertial>
+
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/middle_l3.stl" />
+ </geometry>
+ <material name="">
+ <color rgba="1 1 1 1" />
+ </material>
</visual>
-
- <collision>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/middle_l3.stl" />
- </geometry>
- </collision>
+
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/middle_l3.stl" />
+ </geometry>
+ </collision>
</link>
-
- <joint name="middle_j3" type="revolute">
- <origin xyz="0.0267 0 0" rpy="0 0 0" />
- <parent link="middle_l2" />
- <child link="middle_l3" />
- <axis xyz="0 0 1" />
+
+ <joint name="middle_j3" type="revolute">
+ <origin xyz="0.0267 0 0" rpy="0 0 0" />
+ <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" />
- <mimic joint="middle_j1" multiplier="1" offset="0" />
+ <mimic joint="middle_j1" multiplier="1" offset="0" />
</joint>
-
- <link name="index_l1">
- <inertial>
- <origin xyz="0.021926 0.00020303 8.9303E-08" rpy="0 0 0" />
- <mass value="0.010346" />
- <inertia ixx="4.6802E-07" ixy="5.7259E-08" ixz="1.3617E-11" iyy="2.4622E-06" iyz="4.7436E-11" izz="2.4327E-06" />
- </inertial>
-
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/index_l1.stl" />
- </geometry>
- <material name="">
- <color rgba="1 1 1 1" />
- </material>
+
+ <link name="index_l1">
+ <inertial>
+ <origin xyz="0.021926 0.00020303 8.9303E-08" rpy="0 0 0" />
+ <mass value="0.010346" />
+ <inertia ixx="4.6802E-07" ixy="5.7259E-08" ixz="1.3617E-11" iyy="2.4622E-06" iyz="4.7436E-11" izz="2.4327E-06" />
+ </inertial>
+
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/index_l1.stl" />
+ </geometry>
+ <material name="">
+ <color rgba="1 1 1 1" />
+ </material>
</visual>
-
- <collision>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/index_l1.stl" />
- </geometry>
- </collision>
- </link>
-
- <joint name="index_j1" type="revolute">
- <origin xyz="0 -0.030847 0.12828" rpy="-3.0402 -1.5533 -1.5708" />
- <parent link="base_link" />
- <child link="index_l1" />
- <axis xyz="0 0 1" />
- <limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />
- </joint>
-
- <link name="index_l2">
- <inertial>
- <origin xyz="0.010872 0.00039808 1.071E-06" rpy="0 0 0" />
- <mass value="0.0052658" />
- <inertia ixx="2.345E-07" ixy="2.5371E-08" ixz="4.0061E-11" iyy="6.303E-07" iyz="1.1054E-10" izz="6.1275E-07" />
- </inertial>
-
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/index_l2.stl" />
- </geometry>
- <material name="">
- <color rgba="1 1 1 1" />
- </material>
- </visual>
-
- <collision>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/index_l2.stl" />
- </geometry>
- </collision>
- </link>
-
- <joint name="index_j2" type="revolute">
- <origin xyz="0.047 0 0" rpy="0 0 0" />
- <parent link="index_l1" />
- <child link="index_l2" />
- <axis xyz="0 0 1" />
+
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/index_l1.stl" />
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="index_j1" type="revolute">
+ <origin xyz="0.12828 0 0.030847" rpy="0.10135 -0.017453 0" />
+ <parent link="base_link" />
+ <child link="index_l1" />
+ <axis xyz="0 0 1" />
+ <limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />
+ </joint>
+
+ <link name="index_l2">
+ <inertial>
+ <origin xyz="0.010872 0.00039808 1.071E-06" rpy="0 0 0" />
+ <mass value="0.0052658" />
+ <inertia ixx="2.345E-07" ixy="2.5371E-08" ixz="4.0061E-11" iyy="6.303E-07" iyz="1.1054E-10" izz="6.1275E-07" />
+ </inertial>
+
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/index_l2.stl" />
+ </geometry>
+ <material name="">
+ <color rgba="1 1 1 1" />
+ </material>
+ </visual>
+
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/index_l2.stl" />
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="index_j2" type="revolute">
+ <origin xyz="0.047 0 0" rpy="0 0 0" />
+ <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" />
- <mimic joint="index_j1" multiplier="1" offset="0" />
- </joint>
-
- <link name="index_l3">
- <inertial>
- <origin xyz="0.0099715 0.00045399 -2.4634E-07" rpy="0 0 0" />
- <mass value="0.0049969" />
- <inertia ixx="1.7179E-07" ixy="2.5186E-08" ixz="7.6038E-12" iyy="4.632E-07" iyz="-6.3738E-11" izz="4.9237E-07" />
- </inertial>
-
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/index_l3.stl" />
- </geometry>
- <material name="">
- <color rgba="1 1 1 1" />
- </material>
- </visual>
-
- <collision>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/index_l3.stl" />
- </geometry>
- </collision>
- </link>
-
- <joint name="index_j3" type="revolute">
- <origin xyz="0.0267 0 0" rpy="0 0 0" />
- <parent link="index_l2" />
- <child link="index_l3" />
- <axis xyz="0 0 1" />
+ <mimic joint="index_j1" multiplier="1" offset="0" />
+ </joint>
+
+ <link name="index_l3">
+ <inertial>
+ <origin xyz="0.0099715 0.00045399 -2.4701E-07" rpy="0 0 0" />
+ <mass value="0.0049969" />
+ <inertia ixx="1.7179E-07" ixy="2.5186E-08" ixz="7.6354E-12" iyy="4.632E-07" iyz="-6.3734E-11" izz="4.9237E-07" />
+ </inertial>
+
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/index_l3.stl" />
+ </geometry>
+ <material name="">
+ <color rgba="1 1 1 1" />
+ </material>
+ </visual>
+
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/index_l3.stl" />
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="index_j3" type="revolute">
+ <origin xyz="0.0267 0 0" rpy="0 0 0" />
+ <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" />
- <mimic joint="index_j1" multiplier="1" offset="0" />
+ <mimic joint="index_j1" multiplier="1" offset="0" />
</joint>
-
- <link name="thumb_l1">
- <inertial>
- <origin xyz="-3.496E-16 0.021473 -0.015879" rpy="0 0 0" />
- <mass value="0.0091302" />
- <inertia ixx="1.8031E-06" ixy="4.0034E-14" ixz="4.2008E-21" iyy="6.4629E-07" iyz="-2.8188E-07" izz="1.5763E-06" />
- </inertial>
-
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/thumb_l1.stl" />
- </geometry>
- <material name="">
- <color rgba="1 1 1 1" />
- </material>
- </visual>
-
- <collision>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/thumb_l1.stl" />
- </geometry>
- </collision>
+
+ <link name="thumb_l1">
+ <inertial>
+ <origin xyz="-3.4976E-16 0.021473 -0.015879" rpy="0 0 0" />
+ <mass value="0.0091302" />
+ <inertia ixx="1.8031E-06" ixy="4.0034E-14" ixz="4.208E-21" iyy="6.4629E-07" iyz="-2.8188E-07" izz="1.5763E-06" />
+ </inertial>
+
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/thumb_l1.stl" />
+ </geometry>
+ <material name="">
+ <color rgba="1 1 1 1" />
+ </material>
+ </visual>
+
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/thumb_l1.stl" />
+ </geometry>
+ </collision>
</link>
-
- <joint name="thumb_j1" type="revolute">
- <origin xyz="-0.00034464 -0.043575 0.070929" rpy="-0.69813 0 -3.1416" />
- <parent link="base_link" />
- <child link="thumb_l1" />
- <axis xyz="0 0 1" />
- <limit lower="0" upper="1.57" effort="0.37" velocity="5.61" />
+
+ <joint name="thumb_j1" type="revolute">
+ <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="0.37" velocity="5.61" />
</joint>
-
- <link name="thumb_l2">
- <inertial>
- <origin xyz="0.021926 0.00020302 9.7353E-08" rpy="0 0 0" />
- <mass value="0.010346" />
- <inertia ixx="4.6802E-07" ixy="5.726E-08" ixz="1.5393E-11" iyy="2.4622E-06" iyz="4.7897E-11" izz="2.4327E-06" />
- </inertial>
-
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/thumb_l2.stl" />
- </geometry>
- <material name="">
- <color rgba="1 1 1 1" />
- </material>
+
+ <link name="thumb_l2">
+ <inertial>
+ <origin xyz="0.021926 0.00020302 9.7353E-08" rpy="0 0 0" />
+ <mass value="0.010346" />
+ <inertia ixx="4.6802E-07" ixy="5.726E-08" ixz="1.5393E-11" iyy="2.4622E-06" iyz="4.7897E-11" izz="2.4327E-06" />
+ </inertial>
+
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/thumb_l2.stl" />
+ </geometry>
+ <material name="">
+ <color rgba="1 1 1 1" />
+ </material>
</visual>
-
- <collision>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/thumb_l2.stl" />
- </geometry>
- </collision>
+
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/thumb_l2.stl" />
+ </geometry>
+ </collision>
</link>
-
- <joint name="thumb_j2" type="revolute">
- <origin xyz="0 0.03 0" rpy="-1.5708 0 0" />
- <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" />
- </joint>
-
- <link name="thumb_l3">
- <inertial>
- <origin xyz="0.0099715 0.00045398 -2.5524E-07" rpy="0 0 0" />
- <mass value="0.004997" />
- <inertia ixx="1.7179E-07" ixy="2.5186E-08" ixz="7.6937E-12" iyy="4.632E-07" iyz="-6.3833E-11" izz="4.9237E-07" />
+
+ <joint name="thumb_j2" type="revolute">
+ <origin xyz="0 0.03 0" rpy="-1.5708 0 0" />
+ <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" />
+ </joint>
+
+ <link name="thumb_l3">
+ <inertial>
+ <origin xyz="0.0099715 0.00045398 -2.5524E-07" rpy="0 0 0" />
+ <mass value="0.004997" />
+ <inertia ixx="1.7179E-07" ixy="2.5186E-08" ixz="7.6937E-12" iyy="4.632E-07" iyz="-6.3833E-11" izz="4.9237E-07" />
</inertial>
-
- <visual>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/thumb_l3.stl" />
- </geometry>
- <material name="">
- <color rgba="1 1 1 1" />
- </material>
- </visual>
-
- <collision>
- <origin xyz="0 0 0" rpy="0 0 0" />
- <geometry>
- <mesh filename="package://miitzhand_description/meshes/thumb_l3.stl" />
- </geometry>
- </collision>
+
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/thumb_l3.stl" />
+ </geometry>
+ <material name="">
+ <color rgba="1 1 1 1" />
+ </material>
+ </visual>
+
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://miitzhand_description/meshes/thumb_l3.stl" />
+ </geometry>
+ </collision>
</link>
-
- <joint name="thumb_j3" type="revolute">
- <origin xyz="0.047 0 0" rpy="0 0 0" />
- <parent link="thumb_l2" />
- <child link="thumb_l3" />
- <axis xyz="0 0 1" />
+
+ <joint name="thumb_j3" type="revolute">
+ <origin xyz="0.047 0 0" rpy="0 0 0" />
+ <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" />
- <mimic joint="thumb_j2" multiplier="1" offset="1.57" />
- </joint>
-
+ <mimic joint="thumb_j2" multiplier="1" offset="1.57" />
+ </joint>
+
<transmission name="thumb1_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="thumb_j1">
<controlPeriod>0.001</controlPeriod>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
</plugin>
-</gazebo>
+</gazebo>
+
</robot>