<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" />
+ <origin xyz="0.12828 -0.0030807 0.030536" rpy="0.10123 0 1.57" />
</joint>
<link name="index_l1">
</link>
<joint name="index_j1" type="revolute">
- <origin xyz="0 0 0" rpy="0.10135 0 0" />
+ <origin xyz="0.0030963 0 0" rpy="0 0 0" />
<parent link="index_l0" />
<child link="index_l1" />
<axis xyz="0 0 1" />
- <limit lower="-1.57" upper="0" effort="1.968989" velocity="5.61" />
+ <limit lower="-3.14" upper="-1.57" effort="1.968989" velocity="5.61" />
<dynamics damping="0.336538" friction="0.075478" />
</joint>
<child link="index_l2" />
<axis xyz="0 0 1" />
<limit lower="-1.57" upper="0" effort="1.968989" velocity="5.61" />
- <mimic joint="index_j1" multiplier="1" offset="0" />
+ <mimic joint="index_j1" multiplier="1" offset="1.57" />
</joint>
<link name="index_l3">
<child link="index_l3" />
<axis xyz="0 0 1" />
<limit lower="-1.57" upper="0" effort="1.968989" velocity="5.61" />
- <mimic joint="index_j1" multiplier="1" offset="0" />
+ <mimic joint="index_j1" multiplier="1" offset="1.57" />
</joint>
<link name="thumb_l0"/>
<joint>index_j2</joint>
<mimicJoint>index_j1</mimicJoint>
<multiplier>1.0</multiplier>
- <offset>0.0</offset>
+ <offset>1.57</offset>
<maxEffort>30.0</maxEffort>
<sensitiveness>0.0</sensitiveness>
</plugin>
<joint>index_j3</joint>
<mimicJoint>index_j1</mimicJoint>
<multiplier>1.0</multiplier>
- <offset>0.0</offset>
+ <offset>1.57</offset>
<maxEffort>30.0</maxEffort>
<sensitiveness>0.0</sensitiveness>
</plugin>