<parent link="world"/>
<child link="origin_link"/>
</joint>
- <link
+<link
name="base_link">
<inertial>
<origin
xyz="-0.00037528 0.0019284 0.070349"
- rpy="0 0 0" />
+ rpy="-1.57 0 -1.57" />
<mass
value="0.16469" />
<inertia
</collision>
</link>
<joint name="origin_joint" type="fixed" >
- <parent link="origin_link"/>
- <child link="base_link"/>
+ <!--<origin
+ xyz="0 0 0"
+ rpy="0 0 0" />-->
+ <parent link="origin_link"/>
+ <child link="base_link"/>
+ <!--<axis
+ xyz="0 0 -1"/>
+ <limit
+ lower="0"
+ upper="0"
+ effort="30"
+ velocity="2" />-->
</joint>
<link
name="little_l1">
<inertial>
<origin
- xyz="-0.01191 0.00021661 -0.02162"
+ xyz="0.02162 0.00021661 8.9881E-05"
rpy="0 0 0" />
<mass
value="0.0096962" />
<inertia
- ixx="2.3836E-06"
- ixy="4.7052E-11"
- ixz="-1.4317E-11"
+ ixx="4.6379E-07"
+ ixy="5.6617E-08"
+ ixz="1.4317E-11"
iyy="2.4105E-06"
- iyz="-5.6617E-08"
- izz="4.6379E-07" />
+ iyz="4.7052E-11"
+ izz="2.3836E-06" />
</inertial>
<visual>
<origin
name="little_j1"
type="revolute">
<origin
- xyz="0.0025843 0.028763 0.1208"
- rpy="-3.0895 -0.087213 -1.6058" />
+ xyz="0.0030031 0.04071 0.11976"
+ rpy="-0.53727 -1.4692 2.0753" />
<parent
link="base_link" />
<child
link="little_l1" />
<axis
- xyz="-1 0 0" />
+ xyz="0 0 -1" />
<limit
lower="0"
upper="1.57"
name="little_l2">
<inertial>
<origin
- xyz="0.011045 -0.00039673 -0.010872"
+ xyz="0.010872 0.00039673 4.8455E-06"
rpy="0 0 0" />
<mass
value="0.0052657" />
<inertia
- ixx="6.1275E-07"
- ixy="2.6274E-10"
+ ixx="2.3451E-07"
+ ixy="2.5431E-08"
ixz="-2.2276E-11"
iyy="6.3027E-07"
- iyz="2.5431E-08"
- izz="2.3451E-07" />
+ iyz="2.6274E-10"
+ izz="6.1275E-07" />
</inertial>
<visual>
<origin
name="little_j2"
type="revolute">
<origin
- xyz="-0.00086261 0 -0.047"
- rpy="-0.0021314 -1.4016E-15 3.1416" />
+ xyz="0.047 0 8.7389E-05"
+ rpy="-7.893E-17 2.7756E-16 0.0021314" />
<parent
link="little_l1" />
<child
link="little_l2" />
<axis
- xyz="1 0 0" />
+ xyz="0 0 -1" />
<limit
lower="0"
upper="1.57"
name="little_l3">
<inertial>
<origin
- xyz="-0.010333 -0.00045398 0.0099715"
+ xyz="0.0099715 0.00045398 1.7079E-05"
rpy="0 0 0" />
<mass
value="0.0049969" />
<inertia
- ixx="4.9237E-07"
- ixy="6.387E-11"
- ixz="7.6183E-12"
+ ixx="1.7179E-07"
+ ixy="2.5186E-08"
+ ixz="7.583E-12"
iyy="4.632E-07"
- iyz="-2.5186E-08"
- izz="1.7179E-07" />
+ iyz="-6.3876E-11"
+ izz="4.9237E-07" />
</inertial>
<visual>
<origin
name="little_j3"
type="revolute">
<origin
- xyz="0.00071495 0 -0.0267"
- rpy="-3.0794 0 3.1416" />
+ xyz="0.0267 0 -1.4947E-05"
+ rpy="2.5847E-16 -9.7145E-17 0.062159" />
<parent
link="little_l2" />
<child
link="little_l3" />
<axis
- xyz="-1 0 0" />
+ xyz="0 0 -1" />
<limit
lower="0"
upper="1.57"
name="ring_l1">
<inertial>
<origin
- xyz="-0.01127 0.00021662 -0.02162"
+ xyz="0.02162 0.00021662 2.961E-05"
rpy="0 0 0" />
<mass
value="0.0096962" />
<inertia
- ixx="2.3836E-06"
- ixy="4.7182E-11"
- ixz="-1.3932E-11"
+ ixx="4.6379E-07"
+ ixy="5.6617E-08"
+ ixz="1.3932E-11"
iyy="2.4105E-06"
- iyz="-5.6617E-08"
- izz="4.6379E-07" />
+ iyz="4.7182E-11"
+ izz="2.3836E-06" />
</inertial>
<visual>
<origin
name="ring_j1"
type="revolute">
<origin
- xyz="-0.003 0.0064525 0.12926"
- rpy="-3.0449 -0.034907 -1.5708" />
+ xyz="-0.003 0.017746 0.12886"
+ rpy="-1.2237 -1.468 2.7962" />
<parent
link="base_link" />
<child
link="ring_l1" />
<axis
- xyz="-1 0 0" />
+ xyz="0 0 -1" />
<limit
lower="0"
upper="1.57"
name="ring_l2">
<inertial>
<origin
- xyz="0.010487 -0.00039673 -0.010872"
+ xyz="0.010872 0.00039673 3.3296E-05"
rpy="0 0 0" />
<mass
value="0.0052657" />
<inertia
- ixx="6.1275E-07"
- ixy="2.624E-10"
+ ixx="2.3451E-07"
+ ixy="2.5431E-08"
ixz="-2.1855E-11"
iyy="6.3027E-07"
- iyz="2.5431E-08"
- izz="2.3451E-07" />
+ iyz="2.624E-10"
+ izz="6.1275E-07" />
</inertial>
<visual>
<origin
name="ring_j2"
type="revolute">
<origin
- xyz="-0.00078134 0 -0.047"
- rpy="0.04204 6.9389E-18 3.1416" />
+ xyz="0.047 0 0"
+ rpy="6.2016E-17 -9.7145E-17 -0.04204" />
<parent
link="ring_l1" />
<child
link="ring_l2" />
<axis
- xyz="1 0 0" />
+ xyz="0 0 -1" />
<limit
lower="0"
upper="1.57"
name="ring_l3">
<inertial>
<origin
- xyz="-0.0098289 -0.00045398 0.0099715"
+ xyz="0.0099715 0.00045398 2.1131E-05"
rpy="0 0 0" />
<mass
value="0.0049969" />
<inertia
- ixx="4.9237E-07"
- ixy="6.3755E-11"
+ ixx="1.7179E-07"
+ ixy="2.5186E-08"
ixz="7.5284E-12"
iyy="4.632E-07"
- iyz="-2.5186E-08"
- izz="1.7179E-07" />
+ iyz="-6.3755E-11"
+ izz="4.9237E-07" />
</inertial>
<visual>
<origin
name="ring_j3"
type="revolute">
<origin
- xyz="0.00066054 0 -0.0267"
- rpy="-3.089 -1.3878E-17 -3.1416" />
+ xyz="0.0267 0 0"
+ rpy="4.9006E-17 -7.6328E-17 0.052588" />
<parent
link="ring_l2" />
<child
link="ring_l3" />
<axis
- xyz="-1 0 0" />
+ xyz="0 0 -1" />
<limit
lower="0"
upper="1.57"
name="middle_l1">
<inertial>
<origin
- xyz="0.0068039 0.00021663 -0.02162"
+ xyz="0.02162 0.00021663 2.3898E-05"
rpy="0 0 0" />
<mass
value="0.0096962" />
<inertia
- ixx="2.3836E-06"
- ixy="4.7346E-11"
- ixz="-1.3411E-11"
+ ixx="4.6379E-07"
+ ixy="5.6616E-08"
+ ixz="1.3411E-11"
iyy="2.4105E-06"
- iyz="-5.6616E-08"
- izz="4.6379E-07" />
+ iyz="4.7346E-11"
+ izz="2.3836E-06" />
</inertial>
<visual>
<origin
name="middle_j1"
type="revolute">
<origin
- xyz="-0.0034154 -0.00020889 0.1285"
- rpy="-3.0417 -8.6736E-19 -1.5097" />
+ xyz="-0.0030015 -0.0069762 0.1285"
+ rpy="-1.5708 -1.4709 -3.0805" />
<parent
link="base_link" />
<child
link="middle_l1" />
<axis
- xyz="-1 0 0" />
+ xyz="0 0 -1" />
<limit
lower="0"
upper="1.57"
name="middle_l2">
<inertial>
<origin
- xyz="-0.0068049 -0.00039803 -0.010872"
+ xyz="0.010872 0.00039803 4.914E-06"
rpy="0 0 0" />
<mass
value="0.0052659" />
<inertia
- ixx="6.1276E-07"
- ixy="1.1335E-10"
+ ixx="2.345E-07"
+ ixy="2.537E-08"
ixz="4.1403E-11"
iyy="6.303E-07"
- iyz="2.537E-08"
- izz="2.345E-07" />
+ iyz="1.1335E-10"
+ izz="6.1276E-07" />
</inertial>
<visual>
<origin
name="middle_j2"
type="revolute">
<origin
- xyz="0 0 -0.047"
- rpy="0.092983 9.1051E-18 3.1416" />
+ xyz="0.047 0 2E-05"
+ rpy="-1.5568E-17 -9.0667E-17 -0.092983" />
<parent
link="middle_l1" />
<child
link="middle_l2" />
<axis
- xyz="1 0 0" />
+ xyz="0 0 -1" />
<limit
lower="0"
upper="1.57"
effort="30"
velocity="2" />
- <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.0068036 -0.00045399 0.0099715"
+ xyz="0.0099715 0.00045399 -1.645E-05"
rpy="0 0 0" />
<mass
value="0.0049969" />
<inertia
- ixx="4.9237E-07"
- ixy="6.3732E-11"
+ ixx="1.7179E-07"
+ ixy="2.5186E-08"
ixz="7.6266E-12"
iyy="4.632E-07"
- iyz="-2.5186E-08"
- izz="1.7179E-07" />
+ iyz="-6.3733E-11"
+ izz="4.9237E-07" />
</inertial>
<visual>
<origin
name="middle_j3"
type="revolute">
<origin
- xyz="0 0 -0.0267"
- rpy="3.135 1.0368E-18 -3.1416" />
+ xyz="0.0267 0 2E-05"
+ rpy="-5.6412E-20 -9.6624E-18 -0.0065785" />
<parent
link="middle_l2" />
<child
link="middle_l3" />
<axis
- xyz="-1 0 0" />
+ xyz="0 0 -1" />
<limit
lower="0"
upper="1.57"
name="index_l1">
<inertial>
<origin
- xyz="0.01165 0.00021663 -0.02162"
+ xyz="0.02162 0.00021663 9.5195E-08"
rpy="0 0 0" />
<mass
value="0.0096962" />
<inertia
- ixx="2.3836E-06"
- ixy="4.7439E-11"
- ixz="-1.3332E-11"
+ ixx="4.6379E-07"
+ ixy="5.6616E-08"
+ ixz="1.3332E-11"
iyy="2.4105E-06"
- iyz="-5.6616E-08"
- izz="4.6379E-07" />
+ iyz="4.744E-11"
+ izz="2.3836E-06" />
</inertial>
<visual>
<origin
name="index_j1"
type="revolute">
<origin
- xyz="-0.0011787 -0.019259 0.12848"
- rpy="-3.0766 0.017364 -1.4694" />
+ xyz="0 -0.030847 0.12828"
+ rpy="-1.8319 -1.5035 -2.7796" />
<parent
link="base_link" />
<child
link="index_l1" />
<axis
- xyz="-1 0 0" />
+ xyz="0 0 -1" />
<limit
lower="0"
upper="1.57"
name="index_l2">
<inertial>
<origin
- xyz="-0.011652 -0.000397 -0.010872"
+ xyz="0.010872 0.000397 2.393E-06"
rpy="0 0 0" />
<mass
value="0.0052656" />
<inertia
- ixx="6.1273E-07"
- ixy="2.5193E-10"
+ ixx="2.345E-07"
+ ixy="2.5427E-08"
ixz="-2.4047E-11"
iyy="6.3027E-07"
- iyz="2.5427E-08"
- izz="2.345E-07" />
+ iyz="2.5193E-10"
+ izz="6.1273E-07" />
</inertial>
<visual>
<origin
name="index_j2"
type="revolute">
<origin
- xyz="0 0 -0.047"
- rpy="0.012461 -2.6021E-15 3.1416" />
+ xyz="0.047 0 0"
+ rpy="2.6728E-15 1.8492E-15 -0.012461" />
<parent
link="index_l1" />
<child
link="index_l2" />
<axis
- xyz="1 0 0" />
+ xyz="0 0 -1" />
<limit
lower="0"
upper="1.57"
effort="30"
velocity="2" />
- <mimic joint="index_j1" multiplier="1" offset="0" />
+ <mimic joint="index_j1" multiplier="1" offset="0" />
</joint>
<link
name="index_l3">
<inertial>
<origin
- xyz="0.01021 -0.000454 0.0099715"
+ xyz="0.0099715 0.000454 7.9673E-05"
rpy="0 0 0" />
<mass
value="0.0049969" />
<inertia
- ixx="4.9237E-07"
- ixy="6.3775E-11"
- ixz="7.6703E-12"
+ ixx="1.7179E-07"
+ ixy="2.5186E-08"
+ ixz="7.6708E-12"
iyy="4.632E-07"
- iyz="-2.5186E-08"
- izz="1.7179E-07" />
+ iyz="-6.3774E-11"
+ izz="4.9237E-07" />
</inertial>
<visual>
<origin
name="index_j3"
type="revolute">
<origin
- xyz="-0.0014401 0 -0.0267"
- rpy="3.0788 -2.6021E-15 -3.1416" />
+ xyz="0.0267 0 -7.9919E-05"
+ rpy="-3.372E-15 -9.194E-16 -0.062827" />
<parent
link="index_l2" />
<child
link="index_l3" />
<axis
- xyz="-1 0 0" />
+ xyz="0 0 -1" />
<limit
lower="0"
upper="1.57"
name="thumb_l1">
<inertial>
<origin
- xyz="-0.00037528 0.0019284 0.070349"
+ xyz="2.3326E-09 0.019805 -0.021977"
rpy="0 0 0" />
<mass
- value="0.16469" />
+ value="0.009042" />
<inertia
- ixx="0.0002481"
- ixy="-3.8181E-06"
- ixz="1.5344E-06"
- iyy="0.00015717"
- iyz="-1.4443E-06"
- izz="0.00010769" />
+ ixx="1.6603E-06"
+ ixy="2.5778E-13"
+ ixz="-4.8917E-14"
+ iyy="7.4098E-07"
+ iyz="-3.6039E-07"
+ izz="1.3315E-06" />
</inertial>
<visual>
<origin
name="thumb_j1"
type="revolute">
<origin
- xyz="-0.00033603 -0.03241 0.056854"
- rpy="3.022 -0.511 1.8117" />
+ xyz="-0.00033603 -0.044407 0.077634"
+ rpy="-0.51406 0.10426 -2.9593" />
<parent
link="base_link" />
<child
link="thumb_l1" />
<axis
- xyz="0 0 -1" />
+ xyz="0 0 1" />
<limit
lower="0"
upper="1.57"
name="thumb_l2">
<inertial>
<origin
- xyz="0.040049 0.00021662 -0.02162"
+ xyz="0.02162 0.00021662 -7.7087E-07"
rpy="0 0 0" />
<mass
value="0.0096962" />
<inertia
- ixx="2.3836E-06"
- ixy="4.7417E-11"
- ixz="-1.3735E-11"
+ ixx="4.6379E-07"
+ ixy="5.6616E-08"
+ ixz="1.3735E-11"
iyy="2.4105E-06"
- iyz="-5.6616E-08"
- izz="4.6379E-07" />
+ iyz="4.7417E-11"
+ izz="2.3836E-06" />
</inertial>
<visual>
<origin
name="thumb_j2"
type="revolute">
<origin
- xyz="0.0095283 0 -0.025675"
- rpy="0.023564 -0.17453 3.1416" />
+ xyz="0 0.029913 -0.0052745"
+ rpy="-3.0088 -1.3947 1.4359" />
<parent
link="thumb_l1" />
<child
link="thumb_l2" />
<axis
- xyz="-1 0 0" />
+ xyz="0 0 -1" />
<limit
lower="0"
upper="1.57"
name="thumb_l3">
<inertial>
<origin
- xyz="0.025569 -0.00045399 0.0099715"
+ xyz="0.0099715 0.00045399 -1.4398E-06"
rpy="0 0 0" />
<mass
value="0.004997" />
<inertia
- ixx="4.9237E-07"
- ixy="6.3228E-11"
+ ixx="1.7179E-07"
+ ixy="2.5185E-08"
ixz="7.7223E-12"
iyy="4.632E-07"
- iyz="-2.5185E-08"
- izz="1.7179E-07" />
+ iyz="-6.3228E-11"
+ izz="4.9237E-07" />
</inertial>
<visual>
<origin
name="thumb_j3"
type="revolute">
<origin
- xyz="0.01448 0 -0.047"
- rpy="-3.1102 5.5511E-17 -1.1102E-16" />
+ xyz="0.047 0 0"
+ rpy="-3.6082E-16 5.5511E-17 0.031398" />
<parent
link="thumb_l2" />
<child
link="thumb_l3" />
<axis
- xyz="-1 0 0" />
+ xyz="0 0 -1" />
<limit
lower="0"
upper="1.57"
effort="30"
velocity="2" />
<mimic joint="thumb_j2" multiplier="1" offset="0" />
- </joint>
+ </joint>
<transmission name="thumb1_transmission">
<type>transmission_interface/SimpleTransmission</type>