Skip to content

Commit

Permalink
Convert panda.srdf to panda.srdf.xacro with arg hand:=true|false
Browse files Browse the repository at this point in the history
This was done since the `moveit_setup_assistant` currently doesn't propagate `xacro` arguments you supply to the `urdf.xacro` file (see [this issue](moveit/moveit#1691)). We need to manually add a way to enable or disable the gripper. This can be done by creating a `panda.srdf.xacro` file.
  • Loading branch information
rickstaa authored and rhaschke committed Sep 28, 2021
1 parent 8566b70 commit f0c2bca
Show file tree
Hide file tree
Showing 7 changed files with 142 additions and 99 deletions.
47 changes: 47 additions & 0 deletions config/hand.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
<?xml version="1.0" encoding="UTF-8"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
<xacro:macro name="hand">
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
<!--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">
<link name="panda_hand"/>
<link name="panda_leftfinger"/>
<link name="panda_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">
<joint name="panda_finger_joint1" value="0.04"/>
<joint name="panda_finger_joint2" value="0.04"/>
</group_state>
<group_state name="close" group="hand">
<joint name="panda_finger_joint1" value="0"/>
<joint name="panda_finger_joint2" value="0"/>
</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)-->
<!--PASSIVE JOINT: Purpose: this element is used to mark joints that are not actuated-->
<passive_joint name="panda_finger_joint2"/>
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
<disable_collisions link1="panda_hand" link2="panda_leftfinger" reason="Adjacent"/>
<disable_collisions link1="panda_hand" link2="panda_link4" reason="Never"/>
<disable_collisions link1="panda_hand" link2="panda_link5" reason="Default"/>
<disable_collisions link1="panda_hand" link2="panda_link6" reason="Never"/>
<disable_collisions link1="panda_hand" link2="panda_link7" reason="Default"/>
<disable_collisions link1="panda_hand" link2="panda_link8" reason="Adjacent"/>
<disable_collisions link1="panda_hand" link2="panda_rightfinger" reason="Adjacent"/>
<disable_collisions link1="panda_leftfinger" link2="panda_link4" reason="Never"/>
<disable_collisions link1="panda_leftfinger" link2="panda_link5" reason="Default"/>
<disable_collisions link1="panda_leftfinger" link2="panda_link6" reason="Never"/>
<disable_collisions link1="panda_leftfinger" link2="panda_link7" reason="Never"/>
<disable_collisions link1="panda_leftfinger" link2="panda_link8" reason="Never"/>
<disable_collisions link1="panda_leftfinger" link2="panda_rightfinger" reason="Default"/>
<disable_collisions link1="panda_link4" link2="panda_rightfinger" reason="Never"/>
<disable_collisions link1="panda_link5" link2="panda_rightfinger" reason="Default"/>
<disable_collisions link1="panda_link6" link2="panda_rightfinger" reason="Never"/>
<disable_collisions link1="panda_link7" link2="panda_rightfinger" reason="Never"/>
<disable_collisions link1="panda_link8" link2="panda_rightfinger" reason="Never"/>
</xacro:macro>
</robot>
97 changes: 0 additions & 97 deletions config/panda.srdf

This file was deleted.

21 changes: 21 additions & 0 deletions config/panda.srdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
<?xml version="1.0" encoding="UTF-8"?>
<!--This does not replace URDF, and is not an extension of URDF.
This is a format for representing semantic information about the robot structure.
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
-->
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
<xacro:include filename="$(find panda_moveit_config)/config/panda_arm.xacro" />
<xacro:panda_arm />

<xacro:arg name="hand" default="false" />

<!--Add the hand if people request it-->
<xacro:if value="$(arg hand)">
<xacro:include filename="$(find panda_moveit_config)/config/hand.xacro" />
<xacro:hand />

<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
<end_effector name="hand" parent_link="panda_link8" group="hand"/>
</xacro:if>

</robot>
62 changes: 62 additions & 0 deletions config/panda_arm.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
<?xml version="1.0" encoding="UTF-8"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
<xacro:macro name="panda_arm">
<!--GROUPS: Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
<!--LINKS: When a link is specified, the parent joint of that link (if it exists) is automatically included-->
<!--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="panda_arm">
<joint name="virtual_joint"/>
<joint name="panda_joint1"/>
<joint name="panda_joint2"/>
<joint name="panda_joint3"/>
<joint name="panda_joint4"/>
<joint name="panda_joint5"/>
<joint name="panda_joint6"/>
<joint name="panda_joint7"/>
<joint name="panda_joint8"/>
</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">
<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.7855"/>
</group_state>
<group_state name="extended" group="panda_arm">
<joint name="panda_joint1" value="0"/>
<joint name="panda_joint2" value="-0.3927"/>
<joint name="panda_joint3" value="0"/>
<joint name="panda_joint4" value="-0.7855"/>
<joint name="panda_joint5" value="0"/>
<joint name="panda_joint6" value="3.142"/>
<joint name="panda_joint7" value="-0.785"/>
</group_state>
<!--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="fixed" parent_frame="world" child_link="panda_link0"/>
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
<disable_collisions link1="panda_link0" link2="panda_link1" reason="Adjacent"/>
<disable_collisions link1="panda_link0" link2="panda_link2" reason="Never"/>
<disable_collisions link1="panda_link0" link2="panda_link3" reason="Never"/>
<disable_collisions link1="panda_link0" link2="panda_link4" reason="Never"/>
<disable_collisions link1="panda_link1" link2="panda_link2" reason="Adjacent"/>
<disable_collisions link1="panda_link1" link2="panda_link3" reason="Default"/>
<disable_collisions link1="panda_link1" link2="panda_link4" reason="Never"/>
<disable_collisions link1="panda_link2" link2="panda_link3" reason="Adjacent"/>
<disable_collisions link1="panda_link2" link2="panda_link4" reason="Never"/>
<disable_collisions link1="panda_link3" link2="panda_link4" reason="Adjacent"/>
<disable_collisions link1="panda_link3" link2="panda_link6" reason="Never"/>
<disable_collisions link1="panda_link4" link2="panda_link5" reason="Adjacent"/>
<disable_collisions link1="panda_link4" link2="panda_link6" reason="Never"/>
<disable_collisions link1="panda_link4" link2="panda_link7" reason="Never"/>
<disable_collisions link1="panda_link4" link2="panda_link8" reason="Never"/>
<disable_collisions link1="panda_link5" link2="panda_link6" reason="Adjacent"/>
<disable_collisions link1="panda_link5" link2="panda_link7" reason="Default"/>
<disable_collisions link1="panda_link6" link2="panda_link7" reason="Adjacent"/>
<disable_collisions link1="panda_link7" link2="panda_link8" reason="Adjacent"/>
</xacro:macro>
</robot>
4 changes: 4 additions & 0 deletions launch/demo.launch
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,9 @@
<!-- By default, we are not in debug mode -->
<arg name="debug" default="false" />

<!-- By default we will load the gripper -->
<arg name="load_gripper" default="true" />

<!-- By default, we will load or override the robot_description -->
<arg name="load_robot_description" default="true"/>

Expand Down Expand Up @@ -51,6 +54,7 @@
<arg name="info" value="true"/>
<arg name="debug" value="$(arg debug)"/>
<arg name="pipeline" value="$(arg pipeline)"/>
<arg name="load_gripper" value="$(arg load_gripper)"/>
<arg name="load_robot_description" value="$(arg load_robot_description)"/>
</include>

Expand Down
5 changes: 5 additions & 0 deletions launch/move_group.launch
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,10 @@

<arg name="capabilities" default=""/>
<arg name="disable_capabilities" default=""/>

<!--Other settings-->
<arg name="load_gripper" default="true" />

<!-- load these non-default MoveGroup capabilities (space seperated) -->
<!--
<arg name="capabilities" value="
Expand All @@ -41,6 +45,7 @@
<!-- load URDF, SRDF and joint_limits configuration -->
<include file="$(dirname)/planning_context.launch">
<arg name="load_robot_description" value="$(arg load_robot_description)" />
<arg name="load_gripper" value="$(arg load_gripper)" />
</include>

<!-- Planning Pipelines -->
Expand Down
5 changes: 3 additions & 2 deletions launch/planning_context.launch
Original file line number Diff line number Diff line change
@@ -1,15 +1,16 @@
<launch>
<!-- By default we do not overwrite the URDF. Change the following to true to change the default behavior -->
<arg name="load_gripper" default="true" />
<arg name="load_robot_description" default="false"/>

<!-- The name of the parameter under which the URDF is loaded -->
<arg name="robot_description" default="robot_description"/>

<!-- Load universal robot description format (URDF) -->
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro hand:=true '$(find franka_description)/robots/panda_arm.urdf.xacro'"/>
<param if="$(arg load_robot_description)" name="$(arg robot_description)" command="xacro hand:=$(arg load_gripper) '$(find franka_description)/robots/panda_arm.urdf.xacro'"/>

<!-- The semantic description that corresponds to the URDF -->
<param name="$(arg robot_description)_semantic" textfile="$(find panda_moveit_config)/config/panda.srdf" />
<param name="$(arg robot_description)_semantic" command="$(find xacro)/xacro '$(find panda_moveit_config)/config/panda.srdf.xacro' hand:=$(arg load_gripper)"/>

<!-- Load updated joint limits (override information from URDF) -->
<group ns="$(arg robot_description)_planning">
Expand Down

0 comments on commit f0c2bca

Please sign in to comment.