<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" />
+ <origin xyz="0.1285 -0.00041437 0.0067917" rpy="0.061087 0 1.5708" />
</joint>
<link name="middle_l1">
</link>
<joint name="middle_j1" type="revolute">
- <origin xyz="0 0 0" rpy="0.465978796285 0 0" />
+ <origin xyz="0.0032071 0 0" rpy="0 0 0" />
<parent link="middle_l0" />
<child link="middle_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="middle_l2" />
<axis xyz="0 0 1" />
<limit lower="-1.57" upper="0" effort="1.968989" velocity="5.61" />
- <mimic joint="middle_j1" multiplier="1" offset="0" />
+ <mimic joint="middle_j1" multiplier="1" offset="1.57" />
</joint>
<link name="middle_l3">
<child link="middle_l3" />
<axis xyz="0 0 1" />
<limit lower="-1.57" upper="0" effort="1.968989" velocity="5.61" />
- <mimic joint="middle_j1" multiplier="1" offset="0" />
+ <mimic joint="middle_j1" multiplier="1" offset="1.57" />
</joint>
<link name="index_l0"/>
<joint>middle_j2</joint>
<mimicJoint>middle_j1</mimicJoint>
<multiplier>1.0</multiplier>
- <offset>0.0</offset>
+ <offset>1.57</offset>
<maxEffort>30.0</maxEffort>
<sensitiveness>0.0</sensitiveness>
</plugin>
<joint>middle_j3</joint>
<mimicJoint>middle_j1</mimicJoint>
<multiplier>1.0</multiplier>
- <offset>0.0</offset>
+ <offset>1.57</offset>
<maxEffort>30.0</maxEffort>
<sensitiveness>0.0</sensitiveness>
</plugin>