fix gripper home pose
This commit is contained in:
parent
4497395032
commit
4eb6b0cd75
2 changed files with 14 additions and 14 deletions
|
@ -45,16 +45,16 @@
|
||||||
<joint name="rasmt_Rot_Z_3" value="0.0521"/>
|
<joint name="rasmt_Rot_Z_3" value="0.0521"/>
|
||||||
</group_state>
|
</group_state>
|
||||||
<group_state name="home_hand" group="rasmt_hand_arm_group">
|
<group_state name="home_hand" group="rasmt_hand_arm_group">
|
||||||
<joint name="rasmt_Slide_1" value="0"/>
|
<joint name="rasmt_Slide_1" value="0.02"/>
|
||||||
<joint name="rasmt_Slide_2" value="0"/>
|
<joint name="rasmt_Slide_2" value="0.02"/>
|
||||||
</group_state>
|
</group_state>
|
||||||
<group_state name="full_open" group="rasmt_hand_arm_group">
|
<group_state name="full_open" group="rasmt_hand_arm_group">
|
||||||
<joint name="rasmt_Slide_1" value="0.04"/>
|
<joint name="rasmt_Slide_1" value="0.06"/>
|
||||||
<joint name="rasmt_Slide_2" value="0.04"/>
|
<joint name="rasmt_Slide_2" value="0.06"/>
|
||||||
</group_state>
|
</group_state>
|
||||||
<group_state name="full_close" group="rasmt_hand_arm_group">
|
<group_state name="full_close" group="rasmt_hand_arm_group">
|
||||||
<joint name="rasmt_Slide_1" value="-0.02"/>
|
<joint name="rasmt_Slide_1" value="0.0"/>
|
||||||
<joint name="rasmt_Slide_2" value="-0.02"/>
|
<joint name="rasmt_Slide_2" value="0.0"/>
|
||||||
</group_state>
|
</group_state>
|
||||||
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
|
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
|
||||||
<!--end_effector name="rasmt_hand" parent_link="rasmt_Dock_Link" group="rasmt_hand_arm_group" parent_group="rasmt_arm_group"/-->
|
<!--end_effector name="rasmt_hand" parent_link="rasmt_Dock_Link" group="rasmt_hand_arm_group" parent_group="rasmt_arm_group"/-->
|
||||||
|
|
|
@ -79,7 +79,7 @@
|
||||||
</inertial>
|
</inertial>
|
||||||
<visual>
|
<visual>
|
||||||
<origin
|
<origin
|
||||||
xyz="0 0 0"
|
xyz="-0.02 0 0"
|
||||||
rpy="0 0 0" />
|
rpy="0 0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh
|
<mesh
|
||||||
|
@ -93,7 +93,7 @@
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<origin
|
<origin
|
||||||
xyz="0 0 0"
|
xyz="-0.02 0 0"
|
||||||
rpy="0 0 0" />
|
rpy="0 0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh
|
<mesh
|
||||||
|
@ -116,8 +116,8 @@
|
||||||
xyz="1 0 0" />
|
xyz="1 0 0" />
|
||||||
<limit
|
<limit
|
||||||
effort="20"
|
effort="20"
|
||||||
lower="-0.02"
|
lower="0.0"
|
||||||
upper="0.04"
|
upper="0.06"
|
||||||
velocity="0.2"/>
|
velocity="0.2"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
|
@ -139,7 +139,7 @@
|
||||||
</inertial>
|
</inertial>
|
||||||
<visual>
|
<visual>
|
||||||
<origin
|
<origin
|
||||||
xyz="0 0 0"
|
xyz="-0.02 0 0"
|
||||||
rpy="0 0 0" />
|
rpy="0 0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh
|
<mesh
|
||||||
|
@ -153,7 +153,7 @@
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<origin
|
<origin
|
||||||
xyz="0 0 0"
|
xyz="-0.02 0 0"
|
||||||
rpy="0 0 0" />
|
rpy="0 0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh
|
<mesh
|
||||||
|
@ -176,8 +176,8 @@
|
||||||
xyz="1 0 0" />
|
xyz="1 0 0" />
|
||||||
<limit
|
<limit
|
||||||
effort="20"
|
effort="20"
|
||||||
lower="-0.02"
|
lower="0.0"
|
||||||
upper="0.04"
|
upper="0.06"
|
||||||
velocity="0.2"/>
|
velocity="0.2"/>
|
||||||
<!--mimic joint="${prefix}_Slide_1"/-->
|
<!--mimic joint="${prefix}_Slide_1"/-->
|
||||||
</joint>
|
</joint>
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue