</link>
<joint name="thumb_j2" type="revolute">
- <origin xyz="0 0.03 0" rpy="1.5708 -1.5708 0" />
+ <origin xyz="0 0.03 0" rpy="-1.5708 0 0" />
<parent link="thumb_l1" />
<child link="thumb_l2" />
<axis xyz="0 0 1" />
- <limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />
+ <limit lower="-3.14" upper="-1.57" effort="0.37" velocity="5.61" />
</joint>
<link name="thumb_l3">
<child link="thumb_l3" />
<axis xyz="0 0 1" />
<limit lower="-1.57" upper="0" effort="0.37" velocity="5.61" />
- <mimic joint="thumb_j2" multiplier="1" offset="0" />
+ <mimic joint="thumb_j2" multiplier="1" offset="1.57" />
</joint>
<transmission name="thumb1_transmission">
<joint>thumb_j3</joint>
<mimicJoint>thumb_j2</mimicJoint>
<multiplier>1.0</multiplier>
- <offset>0.0</offset>
+ <offset>1.57</offset>
<maxEffort>30.0</maxEffort>
<sensitiveness>0.0</sensitiveness>
</plugin>