Alterações nos arquivos URDF e meshes.
authorGabriel Schmitz <gschmitz@ece.ufrgs.br>
Tue, 15 Jan 2019 03:18:49 +0000 (01:18 -0200)
committerGabriel Schmitz <gschmitz@ece.ufrgs.br>
Tue, 15 Jan 2019 03:18:49 +0000 (01:18 -0200)
18 files changed:
miitzhand_description/CMakeLists.txt
miitzhand_description/meshes/index_l1.STL [moved from miitzhand_description/meshes/Ind_L1.STL with 100% similarity]
miitzhand_description/meshes/index_l2.STL [moved from miitzhand_description/meshes/Ind_L2.STL with 100% similarity]
miitzhand_description/meshes/index_l3.STL [moved from miitzhand_description/meshes/Ind_L3.STL with 100% similarity]
miitzhand_description/meshes/little_l1.STL [moved from miitzhand_description/meshes/Min_L1.STL with 100% similarity]
miitzhand_description/meshes/little_l2.STL [moved from miitzhand_description/meshes/Min_L2.STL with 100% similarity]
miitzhand_description/meshes/little_l3.STL [moved from miitzhand_description/meshes/Min_L3.STL with 100% similarity]
miitzhand_description/meshes/middle_l1.STL [moved from miitzhand_description/meshes/Med_L1.STL with 100% similarity]
miitzhand_description/meshes/middle_l2.STL [moved from miitzhand_description/meshes/Med_L2.STL with 100% similarity]
miitzhand_description/meshes/middle_l3.STL [moved from miitzhand_description/meshes/Med_L3.STL with 100% similarity]
miitzhand_description/meshes/ring_l1.STL [moved from miitzhand_description/meshes/Ane_L1.STL with 100% similarity]
miitzhand_description/meshes/ring_l2.STL [moved from miitzhand_description/meshes/Ane_L2.STL with 100% similarity]
miitzhand_description/meshes/ring_l3.STL [moved from miitzhand_description/meshes/Ane_L3.STL with 100% similarity]
miitzhand_description/meshes/thumb_l1.STL [moved from miitzhand_description/meshes/Pol_L1.STL with 100% similarity]
miitzhand_description/meshes/thumb_l2.STL [moved from miitzhand_description/meshes/Pol_L2.STL with 100% similarity]
miitzhand_description/meshes/thumb_l3.STL [moved from miitzhand_description/meshes/Pol_L3.STL with 100% similarity]
miitzhand_description/package.xml
miitzhand_description/urdf/miitzhand.urdf

index 80ee2ff..48b5c00 100644 (file)
@@ -8,15 +8,13 @@ project(miitzhand_description)
 ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
 ## is used, also find other catkin packages
 find_package(catkin REQUIRED COMPONENTS
-  roscpp
-  rospy
-)
-find_package(catkin REQUIRED COMPONENTS
-  controller_interface
-  effort_controllers
   urdf
+  rviz
 )
-find_package(cmake_modules REQUIRED)
+find_package(t2f_ros)
+find_package(robot_state_controller)
+
+
 ## System dependencies are found with CMake's conventions
 # find_package(Boost REQUIRED COMPONENTS system)
 
@@ -108,7 +106,7 @@ find_package(cmake_modules REQUIRED)
 ## DEPENDS: system dependencies of this project that dependent projects also need
 catkin_package(
    LIBRARIES ${PROJECT_NAME}
-   CATKIN_DEPENDS controller_interface control_msgs urdf
+   CATKIN_DEPENDS urdf t2f_ros rviz robot_state_controller
 #  INCLUDE_DIRS include
 #  LIBRARIES gabrielquanser_controllers
 #  CATKIN_DEPENDS roscpp rospy
index 3c3d886..891397d 100644 (file)
   <license>MIT</license>
 
   <!--   <test_depend>gtest</test_depend> -->
-   <buildtool_depend>catkin</buildtool_depend>
+  <buildtool_depend>catkin</buildtool_depend>
 
-  <build_depend>controller_interface</build_depend>
-  <build_depend>effort_controllers</build_depend>
-  <build_depend>roscpp</build_depend>
-  <build_depend>rospy</build_depend>
-  <build_depend>control_msgs</build_depend>
   <build_depend>urdf</build_depend>
-  <build_depend>cmake_modules</build_depend>
+  <build_depend>robot_state_controller</build_depend>
+  <build_depend>t2f_ros</build_depend>
+  <build_depend>rviz</build_depend>
 
-  <run_depend>cmake_modules</run_depend>
-  <run_depend>roscpp</run_depend>
-  <run_depend>rospy</run_depend>
   <run_depend>urdf</run_depend>
-  <run_depend>control_msgs</run_depend>
-  <run_depend>controller_interface</run_depend>
-  <run_depend>controller_manager</run_depend>
-  <run_depend>effort_controllers</run_depend>
+  <run_depend>robot_state_controller</run_depend>
   <run_depend>joint_state_controller</run_depend>
-  <run_depend>joint_position_controller</run_depend>
+  <run_depend>t2f_ros</run_depend>
+  <run_depend>rviz</run_depend>
 
 
   <!-- The export tag contains other, unspecified, tags -->
index 948fb0b..feee073 100644 (file)
@@ -53,7 +53,7 @@
                <child link="base_link"/>
 </joint>
   <link
-    name="Min_L1">
+    name="little_l1">
     <inertial>
       <origin
         xyz="-0.01191 0.00021661 -0.02162"
@@ -74,7 +74,7 @@
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Min_L1.STL" />
+          filename="package://miitzhand_description/meshes/little_l1.STL" />
       </geometry>
       <material
         name="">
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Min_L1.STL" />
+          filename="package://miitzhand_description/meshes/little_l1.STL" />
       </geometry>
     </collision>
   </link>
   <joint
-    name="Min_J1"
+    name="little_j1"
     type="revolute">
     <origin
       xyz="0.0025843 0.028763 0.1208"
     <parent
       link="base_link" />
     <child
-      link="Min_L1" />
+      link="little_l1" />
     <axis
       xyz="-1 0 0" />
     <limit
       velocity="2" />
   </joint>
   <link
-    name="Min_L2">
+    name="little_l2">
     <inertial>
       <origin
         xyz="0.011045 -0.00039673 -0.010872"
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Min_L2.STL" />
+          filename="package://miitzhand_description/meshes/little_l2.STL" />
       </geometry>
       <material
         name="">
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Min_L2.STL" />
+          filename="package://miitzhand_description/meshes/little_l2.STL" />
       </geometry>
     </collision>
   </link>
   <joint
-    name="Min_J2"
+    name="little_j2"
     type="revolute">
     <origin
       xyz="-0.00086261 0 -0.047"
       rpy="-0.0021314 -1.4016E-15 3.1416" />
     <parent
-      link="Min_L1" />
+      link="little_l1" />
     <child
-      link="Min_L2" />
+      link="little_l2" />
     <axis
       xyz="1 0 0" />
     <limit
       upper="1.57"
       effort="30"
       velocity="2" />
-      <mimic joint="Min_J1" multiplier="1" offset="0" />
+      <mimic joint="little_j1" multiplier="1" offset="0" />
   </joint>
   <link
-    name="Min_L3">
+    name="little_l3">
     <inertial>
       <origin
         xyz="-0.010333 -0.00045398 0.0099715"
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Min_L3.STL" />
+          filename="package://miitzhand_description/meshes/little_l3.STL" />
       </geometry>
       <material
         name="">
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Min_L3.STL" />
+          filename="package://miitzhand_description/meshes/little_l3.STL" />
       </geometry>
     </collision>
   </link>
   <joint
-    name="Min_J3"
+    name="little_j3"
     type="revolute">
     <origin
       xyz="0.00071495 0 -0.0267"
       rpy="-3.0794 0 3.1416" />
     <parent
-      link="Min_L2" />
+      link="little_l2" />
     <child
-      link="Min_L3" />
+      link="little_l3" />
     <axis
       xyz="-1 0 0" />
     <limit
       upper="1.57"
       effort="30"
       velocity="2" />
-      <mimic joint="Min_J1" multiplier="1" offset="0" />
+      <mimic joint="little_j1" multiplier="1" offset="0" />
   </joint>
   <link
-    name="Ane_L1">
+    name="ring_l1">
     <inertial>
       <origin
         xyz="-0.01127 0.00021662 -0.02162"
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Ane_L1.STL" />
+          filename="package://miitzhand_description/meshes/ring_l1.STL" />
       </geometry>
       <material
         name="">
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Ane_L1.STL" />
+          filename="package://miitzhand_description/meshes/ring_l1.STL" />
       </geometry>
     </collision>
   </link>
   <joint
-    name="Ane_J1"
+    name="ring_j1"
     type="revolute">
     <origin
       xyz="-0.003 0.0064525 0.12926"
     <parent
       link="base_link" />
     <child
-      link="Ane_L1" />
+      link="ring_l1" />
     <axis
       xyz="-1 0 0" />
     <limit
       velocity="2" />
   </joint>
   <link
-    name="Ane_L2">
+    name="ring_l2">
     <inertial>
       <origin
         xyz="0.010487 -0.00039673 -0.010872"
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Ane_L2.STL" />
+          filename="package://miitzhand_description/meshes/ring_l2.STL" />
       </geometry>
       <material
         name="">
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Ane_L2.STL" />
+          filename="package://miitzhand_description/meshes/ring_l2.STL" />
       </geometry>
     </collision>
   </link>
   <joint
-    name="Ane_J2"
+    name="ring_j2"
     type="revolute">
     <origin
       xyz="-0.00078134 0 -0.047"
       rpy="0.04204 6.9389E-18 3.1416" />
     <parent
-      link="Ane_L1" />
+      link="ring_l1" />
     <child
-      link="Ane_L2" />
+      link="ring_l2" />
     <axis
       xyz="1 0 0" />
     <limit
       upper="1.57"
       effort="30"
       velocity="2" />
-      <mimic joint="Ane_J1" multiplier="1" offset="0" />
+      <mimic joint="ring_j1" multiplier="1" offset="0" />
   </joint>
   <link
-    name="Ane_L3">
+    name="ring_l3">
     <inertial>
       <origin
         xyz="-0.0098289 -0.00045398 0.0099715"
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Ane_L3.STL" />
+          filename="package://miitzhand_description/meshes/ring_l3.STL" />
       </geometry>
       <material
         name="">
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Ane_L3.STL" />
+          filename="package://miitzhand_description/meshes/ring_l3.STL" />
       </geometry>
     </collision>
   </link>
   <joint
-    name="Ane_J3"
+    name="ring_j3"
     type="revolute">
     <origin
       xyz="0.00066054 0 -0.0267"
       rpy="-3.089 -1.3878E-17 -3.1416" />
     <parent
-      link="Ane_L2" />
+      link="ring_l2" />
     <child
-      link="Ane_L3" />
+      link="ring_l3" />
     <axis
       xyz="-1 0 0" />
     <limit
       upper="1.57"
       effort="30"
       velocity="2" />
-      <mimic joint="Ane_J1" multiplier="1" offset="0" />
+      <mimic joint="ring_j1" multiplier="1" offset="0" />
   </joint>
   <link
-    name="Med_L1">
+    name="middle_l1">
     <inertial>
       <origin
         xyz="0.0068039 0.00021663 -0.02162"
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Med_L1.STL" />
+          filename="package://miitzhand_description/meshes/middle_l1.STL" />
       </geometry>
       <material
         name="">
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Med_L1.STL" />
+          filename="package://miitzhand_description/meshes/middle_l1.STL" />
       </geometry>
     </collision>
   </link>
   <joint
-    name="Med_J1"
+    name="middle_j1"
     type="revolute">
     <origin
       xyz="-0.0034154 -0.00020889 0.1285"
     <parent
       link="base_link" />
     <child
-      link="Med_L1" />
+      link="middle_l1" />
     <axis
       xyz="-1 0 0" />
     <limit
       velocity="2" />
   </joint>
   <link
-    name="Med_L2">
+    name="middle_l2">
     <inertial>
       <origin
         xyz="-0.0068049 -0.00039803 -0.010872"
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Med_L2.STL" />
+          filename="package://miitzhand_description/meshes/middle_l2.STL" />
       </geometry>
       <material
         name="">
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Med_L2.STL" />
+          filename="package://miitzhand_description/meshes/middle_l2.STL" />
       </geometry>
     </collision>
   </link>
   <joint
-    name="Med_J2"
+    name="middle_j2"
     type="revolute">
     <origin
       xyz="0 0 -0.047"
       rpy="0.092983 9.1051E-18 3.1416" />
     <parent
-      link="Med_L1" />
+      link="middle_l1" />
     <child
-      link="Med_L2" />
+      link="middle_l2" />
     <axis
       xyz="1 0 0" />
     <limit
       upper="1.57"
       effort="30"
       velocity="2" />
-    <mimic joint="Med_J1" multiplier="1" offset="0" />
+    <mimic joint="middle_j1" multiplier="1" offset="0" />
   </joint>
   <link
-    name="Med_L3">
+    name="middle_l3">
     <inertial>
       <origin
         xyz="0.0068036 -0.00045399 0.0099715"
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Med_L3.STL" />
+          filename="package://miitzhand_description/meshes/middle_l3.STL" />
       </geometry>
       <material
         name="">
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Med_L3.STL" />
+          filename="package://miitzhand_description/meshes/middle_l3.STL" />
       </geometry>
     </collision>
   </link>
   <joint
-    name="Med_J3"
+    name="middle_j3"
     type="revolute">
     <origin
       xyz="0 0 -0.0267"
       rpy="3.135 1.0368E-18 -3.1416" />
     <parent
-      link="Med_L2" />
+      link="middle_l2" />
     <child
-      link="Med_L3" />
+      link="middle_l3" />
     <axis
       xyz="-1 0 0" />
     <limit
       upper="1.57"
       effort="30"
       velocity="2" />
-      <mimic joint="Med_J1" multiplier="1" offset="0" />
+      <mimic joint="middle_j1" multiplier="1" offset="0" />
   </joint>
   <link
-    name="Ind_L1">
+    name="index_l1">
     <inertial>
       <origin
         xyz="0.01165 0.00021663 -0.02162"
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Ind_L1.STL" />
+          filename="package://miitzhand_description/meshes/index_l1.STL" />
       </geometry>
       <material
         name="">
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Ind_L1.STL" />
+          filename="package://miitzhand_description/meshes/index_l1.STL" />
       </geometry>
     </collision>
   </link>
   <joint
-    name="Ind_J1"
+    name="index_j1"
     type="revolute">
     <origin
       xyz="-0.0011787 -0.019259 0.12848"
     <parent
       link="base_link" />
     <child
-      link="Ind_L1" />
+      link="index_l1" />
     <axis
       xyz="-1 0 0" />
     <limit
       velocity="2" />
   </joint>
   <link
-    name="Ind_L2">
+    name="index_l2">
     <inertial>
       <origin
         xyz="-0.011652 -0.000397 -0.010872"
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Ind_L2.STL" />
+          filename="package://miitzhand_description/meshes/index_l2.STL" />
       </geometry>
       <material
         name="">
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Ind_L2.STL" />
+          filename="package://miitzhand_description/meshes/index_l2.STL" />
       </geometry>
     </collision>
   </link>
   <joint
-    name="Ind_J2"
+    name="index_j2"
     type="revolute">
     <origin
       xyz="0 0 -0.047"
       rpy="0.012461 -2.6021E-15 3.1416" />
     <parent
-      link="Ind_L1" />
+      link="index_l1" />
     <child
-      link="Ind_L2" />
+      link="index_l2" />
     <axis
       xyz="1 0 0" />
     <limit
       upper="1.57"
       effort="30"
       velocity="2" />
-    <mimic joint="Ind_J1" multiplier="1" offset="0" />
+    <mimic joint="index_j1" multiplier="1" offset="0" />
   </joint>
   <link
-    name="Ind_L3">
+    name="index_l3">
     <inertial>
       <origin
         xyz="0.01021 -0.000454 0.0099715"
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Ind_L3.STL" />
+          filename="package://miitzhand_description/meshes/index_l3.STL" />
       </geometry>
       <material
         name="">
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Ind_L3.STL" />
+          filename="package://miitzhand_description/meshes/index_l3.STL" />
       </geometry>
     </collision>
   </link>
   <joint
-    name="Ind_J3"
+    name="index_j3"
     type="revolute">
     <origin
       xyz="-0.0014401 0 -0.0267"
       rpy="3.0788 -2.6021E-15 -3.1416" />
     <parent
-      link="Ind_L2" />
+      link="index_l2" />
     <child
-      link="Ind_L3" />
+      link="index_l3" />
     <axis
       xyz="-1 0 0" />
     <limit
       upper="1.57"
       effort="30"
       velocity="2" />
-      <mimic joint="Ind_J1" multiplier="1" offset="0" />
+      <mimic joint="index_j1" multiplier="1" offset="0" />
   </joint>
   <link
-    name="Pol_L1">
+    name="thumb_l1">
     <inertial>
       <origin
         xyz="-0.00037528 0.0019284 0.070349"
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Pol_L1.STL" />
+          filename="package://miitzhand_description/meshes/thumb_l1.STL" />
       </geometry>
       <material
         name="">
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Pol_L1.STL" />
+          filename="package://miitzhand_description/meshes/thumb_l1.STL" />
       </geometry>
     </collision>
   </link>
   <joint
-    name="Pol_J1"
+    name="thumb_j1"
     type="revolute">
     <origin
       xyz="-0.00033603 -0.03241 0.056854"
     <parent
       link="base_link" />
     <child
-      link="Pol_L1" />
+      link="thumb_l1" />
     <axis
       xyz="0 0 -1" />
     <limit
       velocity="2" />
   </joint>
   <link
-    name="Pol_L2">
+    name="thumb_l2">
     <inertial>
       <origin
         xyz="0.040049 0.00021662 -0.02162"
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Pol_L2.STL" />
+          filename="package://miitzhand_description/meshes/thumb_l2.STL" />
       </geometry>
       <material
         name="">
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Pol_L2.STL" />
+          filename="package://miitzhand_description/meshes/thumb_l2.STL" />
       </geometry>
     </collision>
   </link>
   <joint
-    name="Pol_J2"
+    name="thumb_j2"
     type="revolute">
     <origin
       xyz="0.0095283 0 -0.025675"
       rpy="0.023564 -0.17453 3.1416" />
     <parent
-      link="Pol_L1" />
+      link="thumb_l1" />
     <child
-      link="Pol_L2" />
+      link="thumb_l2" />
     <axis
       xyz="-1 0 0" />
     <limit
       velocity="2" />
   </joint>
   <link
-    name="Pol_L3">
+    name="thumb_l3">
     <inertial>
       <origin
         xyz="0.025569 -0.00045399 0.0099715"
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Pol_L3.STL" />
+          filename="package://miitzhand_description/meshes/thumb_l3.STL" />
       </geometry>
       <material
         name="">
         rpy="0 0 0" />
       <geometry>
         <mesh
-          filename="package://miitzhand_description/meshes/Pol_L3.STL" />
+          filename="package://miitzhand_description/meshes/thumb_l3.STL" />
       </geometry>
     </collision>
   </link>
   <joint
-    name="Pol_J3"
+    name="thumb_j3"
     type="revolute">
     <origin
       xyz="0.01448 0 -0.047"
       rpy="-3.1102 5.5511E-17 -1.1102E-16" />
     <parent
-      link="Pol_L2" />
+      link="thumb_l2" />
     <child
-      link="Pol_L3" />
+      link="thumb_l3" />
     <axis
       xyz="-1 0 0" />
     <limit
       upper="1.57"
       effort="30"
       velocity="2" />
-      <mimic joint="Pol_J2" multiplier="1" offset="0" />
+      <mimic joint="thumb_j2" multiplier="1" offset="0" />
   </joint>
-<transmission name="Pol1_transmission">
+
+<transmission name="thumb1_transmission">
         <type>transmission_interface/SimpleTransmission</type>
-        <joint name="Pol_J1">
+        <joint name="thumb_j1">
                 <hardwareInterface>EffortJointInterface</hardwareInterface>
         </joint>
-        <actuator name="Pol1_motor">
+        <actuator name="thumb1_motor">
                 <mechanicalReduction>1</mechanicalReduction>
         </actuator>
-  </transmission>
+</transmission>
 
-<transmission name="Pol2_transmission">
+<transmission name="thumb2_transmission">
         <type>transmission_interface/SimpleTransmission</type>
-        <joint name="Pol_J2">
+        <joint name="thumb_j2">
                 <hardwareInterface>EffortJointInterface</hardwareInterface>
         </joint>
-        <actuator name="Pol2_motor">
+        <actuator name="thumb2_motor">
                 <mechanicalReduction>1</mechanicalReduction>
         </actuator>
-  </transmission>
+</transmission>
 
-<transmission name="Pol3_transmission">
+<transmission name="thumb3_transmission">
         <type>transmission_interface/SimpleTransmission</type>
-        <joint name="Pol_J3">
+        <joint name="thumb_j3">
                 <hardwareInterface>EffortJointInterface</hardwareInterface>
         </joint>
-        <actuator name="Pol3_motor">
+        <actuator name="thumb3_motor">
                 <mechanicalReduction>1</mechanicalReduction>
         </actuator>
-  </transmission>
-
-    <gazebo>
+</transmission>
 
+<gazebo>
   <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">
-  <joint>Pol_J3</joint>
-  <mimicJoint>Pol_J2</mimicJoint>
-  <multiplier>1.0</multiplier>
-  <offset>0.0</offset>
-  <maxEffor>30.0</maxEffor>
-  <sensitiveness>0.0</sensitiveness>
+       <joint>thumb_j3</joint>
+       <mimicJoint>thumb_j2</mimicJoint>
+       <multiplier>1.0</multiplier>
+       <offset>0.0</offset>
+       <maxEffort>30.0</maxEffort>
+       <sensitiveness>0.0</sensitiveness>
   </plugin>
-  </gazebo>
+</gazebo>
 
-<transmission name="Ind1_transmission">
+<transmission name="index1_transmission">
         <type>transmission_interface/SimpleTransmission</type>
-        <joint name="Ind_J1">
+        <joint name="index_j1">
                 <hardwareInterface>EffortJointInterface</hardwareInterface>
         </joint>
-        <actuator name="Ind1_motor">
+        <actuator name="index1_motor">
                 <mechanicalReduction>1</mechanicalReduction>
         </actuator>
-  </transmission>
+</transmission>
 
-<transmission name="Ind2_transmission">
+<transmission name="index2_transmission">
         <type>transmission_interface/SimpleTransmission</type>
-        <joint name="Ind_J2">
+        <joint name="index_j2">
                 <hardwareInterface>EffortJointInterface</hardwareInterface>
         </joint>
-        <actuator name="Ind2_motor">
+        <actuator name="index2_motor">
                 <mechanicalReduction>1</mechanicalReduction>
         </actuator>
-  </transmission>
+</transmission>
 
-  <gazebo>
+<gazebo>
   <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">
-  <joint>Ind_J2</joint>
-  <mimicJoint>Ind_J1</mimicJoint>
-  <multiplier>1.0</multiplier>
-  <offset>0.0</offset>
-  <maxEffor>30.0</maxEffor>
-  <sensitiveness>0.0</sensitiveness>
+       <joint>index_j2</joint>
+       <mimicJoint>index_j1</mimicJoint>
+       <multiplier>1.0</multiplier>
+       <offset>0.0</offset>
+       <maxEffort>30.0</maxEffort>
+       <sensitiveness>0.0</sensitiveness>
   </plugin>
-  </gazebo>
+</gazebo>
 
-<transmission name="Ind3_transmission">
+<transmission name="index3_transmission">
         <type>transmission_interface/SimpleTransmission</type>
-        <joint name="Ind_J3">
+        <joint name="index_j3">
                 <hardwareInterface>EffortJointInterface</hardwareInterface>
         </joint>
-        <actuator name="Ind3_motor">
+        <actuator name="index3_motor">
                 <mechanicalReduction>1</mechanicalReduction>
         </actuator>
-  </transmission>
+</transmission>
 
-  <gazebo>
+<gazebo>
   <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">
-  <joint>Ind_J3</joint>
-  <mimicJoint>Ind_J1</mimicJoint>
-  <multiplier>1.0</multiplier>
-  <offset>0.0</offset>
-  <maxEffor>30.0</maxEffor>
-  <sensitiveness>0.0</sensitiveness>
+       <joint>index_j3</joint>
+       <mimicJoint>index_j1</mimicJoint>
+       <multiplier>1.0</multiplier>
+       <offset>0.0</offset>
+       <maxEffort>30.0</maxEffort>
+       <sensitiveness>0.0</sensitiveness>
   </plugin>
-  </gazebo>
+</gazebo>
 
-<transmission name="Med1_transmission">
+<transmission name="middle1_transmission">
         <type>transmission_interface/SimpleTransmission</type>
-        <joint name="Med_J1">
+        <joint name="middle_j1">
                 <hardwareInterface>EffortJointInterface</hardwareInterface>
         </joint>
-        <actuator name="Med1_motor">
+        <actuator name="middle1_motor">
                 <mechanicalReduction>1</mechanicalReduction>
         </actuator>
-  </transmission>
+</transmission>
 
-<transmission name="Med2_transmission">
+<transmission name="middle2_transmission">
         <type>transmission_interface/SimpleTransmission</type>
-        <joint name="Med_J2">
+        <joint name="middle_j2">
                 <hardwareInterface>EffortJointInterface</hardwareInterface>
         </joint>
-        <actuator name="Med2_motor">
+        <actuator name="middle2_motor">
                 <mechanicalReduction>1</mechanicalReduction>
         </actuator>
-  </transmission>
+</transmission>
 
-  <gazebo>
+<gazebo>
   <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">
-  <joint>Med_J2</joint>
-  <mimicJoint>Med_J1</mimicJoint>
-  <multiplier>1.0</multiplier>
-  <offset>0.0</offset>
-  <maxEffor>30.0</maxEffor>
-  <sensitiveness>0.0</sensitiveness>
+       <joint>middle_j2</joint>
+       <mimicJoint>middle_j1</mimicJoint>
+       <multiplier>1.0</multiplier>
+       <offset>0.0</offset>
+       <maxEffort>30.0</maxEffort>
+       <sensitiveness>0.0</sensitiveness>
   </plugin>
-  </gazebo>
+</gazebo>
 
-<transmission name="Med3_transmission">
+<transmission name="middle3_transmission">
         <type>transmission_interface/SimpleTransmission</type>
-        <joint name="Med_J3">
+        <joint name="middle_j3">
                 <hardwareInterface>EffortJointInterface</hardwareInterface>
         </joint>
-        <actuator name="Med3_motor">
+        <actuator name="middle3_motor">
                 <mechanicalReduction>1</mechanicalReduction>
         </actuator>
-  </transmission>
+</transmission>
 
-  <gazebo>
+<gazebo>
   <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">
-  <joint>Med_J3</joint>
-  <mimicJoint>Med_J1</mimicJoint>
-  <multiplier>1.0</multiplier>
-  <offset>0.0</offset>
-  <maxEffor>30.0</maxEffor>
-  <sensitiveness>0.0</sensitiveness>
+       <joint>middle_j3</joint>
+       <mimicJoint>middle_j1</mimicJoint>
+       <multiplier>1.0</multiplier>
+       <offset>0.0</offset>
+       <maxEffort>30.0</maxEffort>
+       <sensitiveness>0.0</sensitiveness>
   </plugin>
-  </gazebo>
+</gazebo>
 
-<transmission name="Ane1_transmission">
+<transmission name="ring1_transmission">
         <type>transmission_interface/SimpleTransmission</type>
-        <joint name="Ane_J1">
+        <joint name="ring_j1">
                 <hardwareInterface>EffortJointInterface</hardwareInterface>
         </joint>
-        <actuator name="Ane1_motor">
+        <actuator name="ring1_motor">
                 <mechanicalReduction>1</mechanicalReduction>
         </actuator>
-  </transmission>
+</transmission>
 
-<transmission name="Ane2_transmission">
+<transmission name="ring2_transmission">
         <type>transmission_interface/SimpleTransmission</type>
-        <joint name="Ane_J2">
+        <joint name="ring_j2">
                 <hardwareInterface>EffortJointInterface</hardwareInterface>
         </joint>
-        <actuator name="Ane2_motor">
+        <actuator name="ring2_motor">
                 <mechanicalReduction>1</mechanicalReduction>
         </actuator>
-  </transmission>
+</transmission>
 
-  <gazebo>
+<gazebo>
   <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">
-  <joint>Ane_J2</joint>
-  <mimicJoint>Ane_J1</mimicJoint>
-  <multiplier>1.0</multiplier>
-  <offset>0.0</offset>
-  <maxEffor>30.0</maxEffor>
-  <sensitiveness>0.0</sensitiveness>
+       <joint>ring_j2</joint>
+       <mimicJoint>ring_j1</mimicJoint>
+       <multiplier>1.0</multiplier>
+       <offset>0.0</offset>
+       <maxEffort>30.0</maxEffort>
+       <sensitiveness>0.0</sensitiveness>
   </plugin>
-  </gazebo>
+</gazebo>
 
-<transmission name="Ane3_transmission">
+<transmission name="ring3_transmission">
         <type>transmission_interface/SimpleTransmission</type>
-        <joint name="Ane_J3">
+        <joint name="ring_j3">
                 <hardwareInterface>EffortJointInterface</hardwareInterface>
         </joint>
-        <actuator name="Ane3_motor">
+        <actuator name="ring3_motor">
                 <mechanicalReduction>1</mechanicalReduction>
         </actuator>
-  </transmission>
+</transmission>
 
-  <gazebo>
+<gazebo>
   <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">
-  <joint>Ane_J3</joint>
-  <mimicJoint>Ane_J1</mimicJoint>
-  <multiplier>1.0</multiplier>
-  <offset>0.0</offset>
-  <maxEffor>30.0</maxEffor>
-  <sensitiveness>0.0</sensitiveness>
+       <joint>ring_j3</joint>
+       <mimicJoint>ring_j1</mimicJoint>
+       <multiplier>1.0</multiplier>
+       <offset>0.0</offset>
+       <maxEffort>30.0</maxEffort>
+       <sensitiveness>0.0</sensitiveness>
   </plugin>
-  </gazebo>
+</gazebo>
 
-<transmission name="Min1_transmission">
+<transmission name="little1_transmission">
         <type>transmission_interface/SimpleTransmission</type>
-        <joint name="Min_J1">
+        <joint name="little_j1">
                 <hardwareInterface>EffortJointInterface</hardwareInterface>
         </joint>
-        <actuator name="Min1_motor">
+        <actuator name="little1_motor">
                 <mechanicalReduction>1</mechanicalReduction>
         </actuator>
-  </transmission>
+</transmission>
 
-<transmission name="Min2_transmission">
+<transmission name="little2_transmission">
         <type>transmission_interface/SimpleTransmission</type>
-        <joint name="Min_J2">
+        <joint name="little_j2">
                 <hardwareInterface>EffortJointInterface</hardwareInterface>
         </joint>
-        <actuator name="Min2_motor">
+        <actuator name="little2_motor">
                 <mechanicalReduction>1</mechanicalReduction>
         </actuator>
-  </transmission>
+</transmission>
 
-  <gazebo>
+<gazebo>
   <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">
-  <joint>Min_J2</joint>
-  <mimicJoint>Min_J1</mimicJoint>
-  <multiplier>1.0</multiplier>
-  <offset>0.0</offset>
-  <maxEffor>30.0</maxEffor>
-  <sensitiveness>0.0</sensitiveness>
+       <joint>little_j2</joint>
+       <mimicJoint>little_j1</mimicJoint>
+       <multiplier>1.0</multiplier>
+       <offset>0.0</offset>
+       <maxEffort>30.0</maxEffort>
+       <sensitiveness>0.0</sensitiveness>
   </plugin>
-  </gazebo>
+</gazebo>
 
-<transmission name="Min3_transmission">
+<transmission name="little3_transmission">
         <type>transmission_interface/SimpleTransmission</type>
-        <joint name="Min_J3">
+        <joint name="little_j3">
                 <hardwareInterface>EffortJointInterface</hardwareInterface>
         </joint>
-        <actuator name="Min3_motor">
+        <actuator name="little3_motor">
                 <mechanicalReduction>1</mechanicalReduction>
         </actuator>
-  </transmission>
+</transmission>
 
-  <gazebo>
+<gazebo>
   <plugin name="mimic_plugin" filename="libroboticsgroup_gazebo_mimic_joint_plugin.so">
-  <joint>Min_J3</joint>
-  <mimicJoint>Min_J1</mimicJoint>
-  <multiplier>1.0</multiplier>
-  <offset>0.0</offset>
-  <maxEffor>30.0</maxEffor>
-  <sensitiveness>0.0</sensitiveness>
+       <joint>little_j3</joint>
+       <mimicJoint>little_j1</mimicJoint>
+       <multiplier>1.0</multiplier>
+       <offset>0.0</offset>
+       <maxEffort>30.0</maxEffort>
+       <sensitiveness>0.0</sensitiveness>
   </plugin>
-  </gazebo>
+</gazebo>
 
 <gazebo>
     <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
-     <robotNamespace>/miitzhand</robotNamespace>
-     <controlPeriod>0.001</controlPeriod>
-     <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
+       <robotNamespace>/miitzhand</robotNamespace>
+       <controlPeriod>0.001</controlPeriod>
+       <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
     </plugin>
-  </gazebo>
+</gazebo>
 </robot>