<child link="base_link"/>
</joint>
+ <link name="little_l0"/>
+
+ <joint name="little_j0" type="fixed">
+ <parent link="base_link"/>
+ <child link="little_l0"/>
+ <origin xyz="0.11977 -0.003 -0.04062" rpy="-0.0737213979639 0.087226 0"/>
+ </joint>
+
<link name="little_l1">
<inertial>
<origin xyz="0.021926 0.00020302 9.6353E-08" rpy="0 0 0" />
<mimic joint="index_j1" multiplier="1" offset="0" />
</joint>
+ <link name="thumb_l0"/>
+
+ <joint name="thumb_j0" type="fixed">
+ <parent link="base_link"/>
+ <child link="thumb_l0"/>
+ <origin xyz="0.070929 0 0.043575" rpy="0 0 1.5708"/>
+ </joint>
+
<link name="thumb_l1">
<inertial>
<origin xyz="-3.4976E-16 0.021473 -0.015879" rpy="0 0 0" />