Skip to content
Snippets Groups Projects
Commit a0f01905 authored by Robert Haschke's avatar Robert Haschke
Browse files

Use arm_id prefix for hand as well

parent 9f0d06d1
No related branches found
No related tags found
No related merge requests found
......@@ -18,5 +18,5 @@ controller_list:
initial: # Define initial robot poses per group
- group: $(arg arm_id)_arm
pose: ready
- group: hand
pose: open
\ No newline at end of file
- group: $(arg arm_id)_hand
pose: open
......@@ -20,17 +20,17 @@
<!--JOINTS: When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
<!--CHAINS: When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group-->
<!--SUBGROUPS: Groups can also be formed by referencing to already defined group names-->
<group name="hand">
<group name="$(arg arm_id)_hand">
<link name="$(arg arm_id)_hand"/>
<link name="$(arg arm_id)_leftfinger"/>
<link name="$(arg arm_id)_rightfinger"/>
</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="open" group="hand">
<group_state name="open" group="$(arg arm_id)_hand">
<joint name="$(arg arm_id)_finger_joint1" value="0.035"/>
<joint name="$(arg arm_id)_finger_joint2" value="0.035"/>
</group_state>
<group_state name="close" group="hand">
<group_state name="close" group="$(arg arm_id)_hand">
<joint name="$(arg arm_id)_finger_joint1" value="0"/>
<joint name="$(arg arm_id)_finger_joint2" value="0"/>
</group_state>
......
......@@ -155,8 +155,8 @@ $(arg arm_id)_arm: &arm_config
- SPARStwo
projection_evaluator: joints($(arg arm_id)_joint1,$(arg arm_id)_joint2)
longest_valid_segment_fraction: 0.005
manipulator: *arm_config
hand:
$(arg arm_id)_manipulator: *arm_config
$(arg arm_id)_hand:
planner_configs:
- AnytimePathShortening
- SBL
......
......@@ -9,9 +9,8 @@
<!-- panda_arm group: eef frame aligned to robot's flanche -->
<xacro:arm name="$(arg arm_id)_arm" tip_link="$(arg arm_id)_link8"/>
<xacro:arg name="hand" default="false" />
<!--Add the hand if people request it-->
<xacro:arg name="hand" default="false" />
<xacro:if value="$(arg hand)">
<!-- manipulator group: eef frame aligned to hand -->
<xacro:arm name="$(arg arm_id)_manipulator" tip_link="$(arg arm_id)_hand_tcp" />
......@@ -19,9 +18,9 @@
<xacro:hand />
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
<end_effector name="hand_tcp" parent_link="$(arg arm_id)_hand_tcp" group="hand" parent_group="$(arg arm_id)_manipulator" />
<end_effector name="$(arg arm_id)_hand_tcp" parent_link="$(arg arm_id)_hand_tcp" group="$(arg arm_id)_hand" parent_group="$(arg arm_id)_manipulator" />
<!-- old end-effector -->
<end_effector name="hand" parent_link="$(arg arm_id)_link8" group="hand" parent_group="$(arg arm_id)_arm" />
<end_effector name="$(arg arm_id)_hand" parent_link="$(arg arm_id)_link8" group="$(arg arm_id)_hand" parent_group="$(arg arm_id)_arm" />
</xacro:if>
</robot>
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment