</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" />
+ <origin xyz="0 0 0" rpy="0.0388143979639 0 0" />
+ <parent link="little_l0" />
<child link="little_l1" />
<axis xyz="0 0 1" />
<limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />
</link>
<joint name="ring_j1" type="revolute">
- <origin xyz="0.12886 0.003 -0.017716" rpy="0 0.034907 0" />
- <parent link="base_link" />
+ <origin xyz="0 0 0" rpy="-0.167747119817 0 0" />
+ <parent link="ring_l0" />
<child link="ring_l1" />
<axis xyz="0 0 1" />
<limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />
</link>
<joint name="middle_j1" type="revolute">
- <origin xyz="0.1285 0.003 0.007" rpy="0.061087 0 0" />
- <parent link="base_link" />
+ <origin xyz="0 0 0" rpy="0.465978796285 0 0" />
+ <parent link="middle_l0" />
<child link="middle_l1" />
<axis xyz="0 0 1" />
<limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />
</link>
<joint name="index_j1" type="revolute">
- <origin xyz="0.12828 0 0.030847" rpy="0.10135 -0.017453 0" />
- <parent link="base_link" />
+ <origin xyz="0 0 0" rpy="0.10135 0 0" />
+ <parent link="index_l0" />
<child link="index_l1" />
<axis xyz="0 0 1" />
<limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />
</link>
<joint name="thumb_j1" type="revolute">
- <origin xyz="0.070929 0.00034464 0.043575" rpy="0.87266 0 1.5708" />
- <parent link="base_link" />
+ <origin xyz="0 0.00034464 0" rpy="0.87266 0 0" />
+ <parent link="thumb_l0" />
<child link="thumb_l1" />
<axis xyz="0 0 1" />
<limit lower="0" upper="1.57" effort="0.37" velocity="5.61" />