<mimic joint="little_j1" multiplier="1" offset="0" />
</joint>
+ <link name="ring_l0"/>
+
+ <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" />
+ </joint>
+
<link name="ring_l1">
<inertial>
<origin xyz="0.021926 0.00020302 9.349E-08" rpy="0 0 0" />
<mimic joint="ring_j1" multiplier="1" offset="0" />
</joint>
+ <link name="middle_l0"/>
+
+ <joint name="middle_j0" type="fixed">
+ <parent link="base_link"/>
+ <child link="middle_l0"/>
+ <origin xyz="0.1285 0.003 0.007" rpy="-0.404891796285 0 0" />
+ </joint>
+
<link name="middle_l1">
<inertial>
<origin xyz="0.021926 0.00020303 9.1214E-08" rpy="0 0 0" />
<mimic joint="middle_j1" multiplier="1" offset="0" />
</joint>
+ <link name="index_l0"/>
+
+ <joint name="index_j0" type="fixed">
+ <parent link="base_link"/>
+ <child link="index_l0"/>
+ <origin xyz="0.12828 0 0.030847" rpy="0 -0.017453 0" />
+ </joint>
+
<link name="index_l1">
<inertial>
<origin xyz="0.021926 0.00020303 8.9303E-08" rpy="0 0 0" />