Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

hand.xacro: Rename ns to prefix #210

Open
wants to merge 2 commits into
base: develop
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions franka_description/robots/dual_panda_example.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -27,10 +27,10 @@

<!-- right arm with gripper -->
<xacro:panda_arm arm_id="$(arg arm_id_1)" connected_to="base" xyz="0 -0.5 1" safety_distance="0.03"/>
<xacro:hand ns="$(arg arm_id_1)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id_1)_link8" safety_distance="0.03"/>
<xacro:hand prefix="$(arg arm_id_1)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id_1)_link8" safety_distance="0.03" />

<!-- left arm with gripper -->
<xacro:panda_arm arm_id="$(arg arm_id_2)" connected_to="base" xyz="0 0.5 1" safety_distance="0.03"/>
<xacro:hand ns="$(arg arm_id_2)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id_2)_link8" safety_distance="0.03"/>
<xacro:hand prefix="$(arg arm_id_2)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id_2)_link8" safety_distance="0.03" />

</robot>
2 changes: 1 addition & 1 deletion franka_description/robots/hand.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="hand">
<xacro:include filename="hand.xacro"/>
<xacro:hand ns="panda" safety_distance="0.03"/>
<xacro:hand prefix="panda" safety_distance="0.03" />
</robot>
39 changes: 22 additions & 17 deletions franka_description/robots/hand.xacro
Original file line number Diff line number Diff line change
@@ -1,15 +1,20 @@
<?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="hand">
<!-- safety_distance: Minimum safety distance in [m] by which the collision volumes are expanded and which is enforced during robot motions -->
<xacro:macro name="hand" params="connected_to:='' ns:='' rpy:='0 0 0' xyz:='0 0 0' safety_distance:=0">
<xacro:macro name="hand" params="connected_to:='' prefix:='' ns:='' rpy:='0 0 0' xyz:='0 0 0' safety_distance:=0">
<xacro:if value="${ns != ''}">
${xacro.warning("xacro:hand: argument ns is deprecated. Use prefix instead.")}
<xacro:property name="prefix" value="${ns}"/>
</xacro:if>

<xacro:unless value="${connected_to == ''}">
<joint name="${ns}_hand_joint" type="fixed">
<joint name="${prefix}_hand_joint" type="fixed">
<parent link="${connected_to}"/>
<child link="${ns}_hand"/>
<child link="${prefix}_hand" />
<origin xyz="${xyz}" rpy="${rpy}"/>
</joint>
</xacro:unless>
<link name="${ns}_hand">
<link name="${prefix}_hand">
<visual>
<geometry>
<mesh filename="package://franka_description/meshes/visual/hand.dae"/>
Expand Down Expand Up @@ -53,41 +58,41 @@
</collision>
</link>
<!-- Define the hand_tcp frame -->
<link name="${ns}_hand_tcp" />
<joint name="${ns}_hand_tcp_joint" type="fixed">
<link name="${prefix}_hand_tcp" />
<joint name="${prefix}_hand_tcp_joint" type="fixed">
<origin xyz="0 0 0.1034" rpy="0 0 0" />
<parent link="${ns}_hand" />
<child link="${ns}_hand_tcp" />
<parent link="${prefix}_hand" />
<child link="${prefix}_hand_tcp" />
</joint>
<link name="${ns}_leftfinger">
<link name="${prefix}_leftfinger">
<visual>
<geometry>
<mesh filename="package://franka_description/meshes/visual/finger.dae"/>
</geometry>
</visual>
</link>
<link name="${ns}_rightfinger">
<link name="${prefix}_rightfinger">
<visual>
<origin xyz="0 0 0" rpy="0 0 ${pi}"/>
<geometry>
<mesh filename="package://franka_description/meshes/visual/finger.dae"/>
</geometry>
</visual>
</link>
<joint name="${ns}_finger_joint1" type="prismatic">
<parent link="${ns}_hand"/>
<child link="${ns}_leftfinger"/>
<joint name="${prefix}_finger_joint1" type="prismatic">
<parent link="${prefix}_hand" />
<child link="${prefix}_leftfinger" />
<origin xyz="0 0 0.0584" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<limit effort="20" lower="0.0" upper="0.04" velocity="0.2"/>
</joint>
<joint name="${ns}_finger_joint2" type="prismatic">
<parent link="${ns}_hand"/>
<child link="${ns}_rightfinger"/>
<joint name="${prefix}_finger_joint2" type="prismatic">
<parent link="${prefix}_hand" />
<child link="${prefix}_rightfinger" />
<origin xyz="0 0 0.0584" rpy="0 0 0"/>
<axis xyz="0 -1 0"/>
<limit effort="20" lower="0.0" upper="0.04" velocity="0.2"/>
<mimic joint="${ns}_finger_joint1" />
<mimic joint="${prefix}_finger_joint1" />
</joint>
</xacro:macro>
</robot>
4 changes: 2 additions & 2 deletions franka_description/robots/panda_arm.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@

<xacro:if value="$(arg hand)">
<xacro:include filename="$(find franka_description)/robots/hand.xacro"/>
<xacro:hand ns="$(arg arm_id)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id)_link8" safety_distance="0.03"/>
<xacro:hand prefix="$(arg arm_id)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id)_link8" safety_distance="0.03" />
</xacro:if>
</xacro:unless>

Expand All @@ -31,7 +31,7 @@
<xacro:panda_arm arm_id="$(arg arm_id)" />

<xacro:if value="$(arg hand)">
<xacro:hand ns="$(arg arm_id)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id)_link8" />
<xacro:hand prefix="$(arg arm_id)" rpy="0 0 ${-pi/4}" connected_to="$(arg arm_id)_link8" />
<xacro:gazebo-joint joint="$(arg arm_id)_finger_joint1" transmission="hardware_interface/EffortJointInterface" />
<xacro:gazebo-joint joint="$(arg arm_id)_finger_joint2" transmission="hardware_interface/EffortJointInterface" />
</xacro:if>
Expand Down
33 changes: 19 additions & 14 deletions franka_description/robots/panda_gazebo.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -270,18 +270,23 @@

</xacro:macro>

<xacro:macro name="hand" params="connected_to:='' ns:='' xyz:='0 0 0' rpy:='0 0 0'">
<xacro:macro name="hand" params="connected_to:='' prefix:='' ns:='' xyz:='0 0 0' rpy:='0 0 0'">
<xacro:include filename="$(find franka_description)/robots/utils.xacro"/>

<xacro:if value="${ns != ''}">
${xacro.warning("xacro:hand: argument ns is deprecated. Use prefix instead.")}
<xacro:property name="prefix" value="${ns}" />
</xacro:if>

<xacro:unless value="${connected_to == ''}">
<joint name="${ns}_hand_joint" type="fixed">
<joint name="${prefix}_hand_joint" type="fixed">
<parent link="${connected_to}"/>
<child link="${ns}_hand"/>
<child link="${prefix}_hand" />
<origin xyz="${xyz}" rpy="${rpy}"/>
</joint>
</xacro:unless>

<link name="${ns}_hand">
<link name="${prefix}_hand">
<visual>
<geometry>
<mesh filename="package://franka_description/meshes/visual/hand.dae"/>
Expand Down Expand Up @@ -332,7 +337,7 @@
</collision>
</xacro:macro>

<link name="${ns}_leftfinger">
<link name="${prefix}_leftfinger">
<xacro:inertia-cylinder mass="15e-3" radius="0.01" h="0.04"/>
<visual>
<geometry>
Expand All @@ -342,7 +347,7 @@
<xacro:finger-collision sign="+" />
</link>

<link name="${ns}_rightfinger">
<link name="${prefix}_rightfinger">
<xacro:inertia-cylinder mass="15e-3" radius="0.01" h="0.04"/>
<visual>
<origin xyz="0 0 0" rpy="0 0 ${pi}"/>
Expand All @@ -355,21 +360,21 @@

<!-- Friction specific material for Rubber/Rubber contact -->
<!-- See: -->
<xacro:gazebo-friction link="${ns}_leftfinger" mu="1.13" />
<xacro:gazebo-friction link="${ns}_rightfinger" mu="1.13" />
<xacro:gazebo-friction link="${prefix}_leftfinger" mu="1.13" />
<xacro:gazebo-friction link="${prefix}_rightfinger" mu="1.13" />

<joint name="${ns}_finger_joint1" type="prismatic">
<parent link="${ns}_hand"/>
<child link="${ns}_leftfinger"/>
<joint name="${prefix}_finger_joint1" type="prismatic">
<parent link="${prefix}_hand" />
<child link="${prefix}_leftfinger" />
<origin xyz="0 0 0.0584" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<limit effort="20" lower="0.0" upper="0.04" velocity="0.2"/>
<dynamics friction="0.0" damping="0.03"/>
</joint>

<joint name="${ns}_finger_joint2" type="prismatic">
<parent link="${ns}_hand"/>
<child link="${ns}_rightfinger"/>
<joint name="${prefix}_finger_joint2" type="prismatic">
<parent link="${prefix}_hand" />
<child link="${prefix}_rightfinger" />
<origin xyz="0 0 0.0584" rpy="0 0 0"/>
<axis xyz="0 -1 0"/>
<limit effort="20" lower="0.0" upper="0.04" velocity="0.2"/>
Expand Down