Skip to content
Snippets Groups Projects
Unverified Commit 2c118fc7 authored by Robert Haschke's avatar Robert Haschke Committed by GitHub
Browse files

Fix initial state of robot (#47)

Define 'extended' state for 'panda_arm' group.
parent fc3d7016
No related branches found
No related tags found
No related merge requests found
......@@ -13,5 +13,7 @@ controller_list:
- panda_finger_joint1
- panda_finger_joint2
initial:
- group: panda_arm_hand
- group: panda_arm
pose: ready
- group: hand
pose: open
......@@ -19,6 +19,15 @@
<joint name="panda_joint6" value="1.571" />
<joint name="panda_joint7" value="0.785" />
</group_state>
<group_state name="extended" group="panda_arm">
<joint name="panda_joint1" value="0" />
<joint name="panda_joint2" value="0" />
<joint name="panda_joint3" value="0" />
<joint name="panda_joint4" value="0" />
<joint name="panda_joint5" value="0" />
<joint name="panda_joint6" value="0" />
<joint name="panda_joint7" value="0.785" />
</group_state>
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
<virtual_joint name="virtual_joint" type="floating" parent_frame="world" child_link="panda_link0" />
......
......@@ -17,25 +17,6 @@
<group name="panda_arm" />
<group name="hand" />
</group>
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
<group_state name="ready" group="panda_arm_hand">
<joint name="panda_joint1" value="0" />
<joint name="panda_joint2" value="-0.785" />
<joint name="panda_joint3" value="0" />
<joint name="panda_joint4" value="-2.356" />
<joint name="panda_joint5" value="0" />
<joint name="panda_joint6" value="1.571" />
<joint name="panda_joint7" value="0.785" />
</group_state>
<group_state name="extended" group="panda_arm_hand">
<joint name="panda_joint1" value="0" />
<joint name="panda_joint2" value="0" />
<joint name="panda_joint3" value="0" />
<joint name="panda_joint4" value="0" />
<joint name="panda_joint5" value="0" />
<joint name="panda_joint6" value="0" />
<joint name="panda_joint7" value="0.785" />
</group_state>
<group_state name="open" group="hand">
<joint name="panda_finger_joint1" value="0.035" />
<joint name="panda_finger_joint2" value="0.035" />
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment