diff --git a/config/arm.xacro b/config/arm.xacro index 23cb073df8cb8576d1021014dae5820d3f9a3f73..e89b0c548717cadf85612b8ea6151da865492b8c 100644 --- a/config/arm.xacro +++ b/config/arm.xacro @@ -1,16 +1,16 @@ <?xml version="1.0" encoding="UTF-8"?> <robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda"> - <xacro:macro name="arm"> + <xacro:macro name="arm" params="name tip_link"> <!--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"> - <chain base_link="panda_link0" tip_link="panda_tool" /> + <group name="${name}"> + <chain base_link="panda_link0" tip_link="${tip_link}" /> </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"> + <group_state name="ready" group="${name}"> <joint name="panda_joint1" value="0" /> <joint name="panda_joint2" value="${-pi/4}" /> <joint name="panda_joint3" value="0" /> @@ -19,7 +19,7 @@ <joint name="panda_joint6" value="${pi/2}" /> <joint name="panda_joint7" value="${pi/4}" /> </group_state> - <group_state name="extended" group="panda_arm"> + <group_state name="extended" group="${name}"> <joint name="panda_joint1" value="0" /> <joint name="panda_joint2" value="0" /> <joint name="panda_joint3" value="0" /> @@ -28,33 +28,34 @@ <joint name="panda_joint6" value="${pi}" /> <joint name="panda_joint7" value="${pi/4}" /> </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_link5" reason="Default" /> - <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"/> - <!-- Fix self-collisions between coarse collision geometries provided by franka_description - (see https://github.com/ros-planning/panda_moveit_config/pull/35#pullrequestreview-390715967). - These collisions are handled by joint limits already and thus can be disabled here. --> - <disable_collisions link1="panda_link5" link2="panda_link8" reason="Default"/> - <disable_collisions link1="panda_link6" link2="panda_link8" reason="Default"/> </xacro:macro> + + <!--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_link5" reason="Default" /> + <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" /> + <!-- Fix self-collisions between coarse collision geometries provided by franka_description + (see https://github.com/ros-planning/panda_moveit_config/pull/35#pullrequestreview-390715967). + These collisions are handled by joint limits already and thus can be disabled here. --> + <disable_collisions link1="panda_link5" link2="panda_link8" reason="Default" /> + <disable_collisions link1="panda_link6" link2="panda_link8" reason="Default" /> </robot> diff --git a/config/panda.srdf.xacro b/config/panda.srdf.xacro index 156a941a06cb33b0a4b7674880dcbe492ffef408..d4b3402c3439208fcc2e2c8c15d2efc00512910f 100644 --- a/config/panda.srdf.xacro +++ b/config/panda.srdf.xacro @@ -5,7 +5,9 @@ --> <robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda"> <xacro:include filename="$(find panda_moveit_config)/config/arm.xacro" /> - <xacro:arm /> + <xacro:arm name="arm" tip_link="panda_tool" /> + <!-- old group name with old end-effector link --> + <xacro:arm name="panda_arm" tip_link="panda_link8"/> <xacro:arg name="hand" default="false" /> @@ -15,7 +17,9 @@ <xacro:hand /> <!--END EFFECTOR: Purpose: Represent information about an end effector.--> - <end_effector name="hand" parent_link="panda_tool" group="hand" parent_group="panda_arm" /> + <end_effector name="tool" parent_link="panda_tool" group="hand" parent_group="arm" /> + <!-- old end-effector --> + <end_effector name="hand" parent_link="panda_link8" group="hand" parent_group="panda_arm" /> </xacro:if> </robot>