Skip to content

Commit

Permalink
Move split link5 into different filename (#75)
Browse files Browse the repository at this point in the history
Revert the changes to panda_arm{,_hand}.urdf.
Instead, copy the changes to new files named link5split.
  • Loading branch information
jwnimmer-tri authored Jan 22, 2025
1 parent 6b67e4c commit 11e0cc1
Show file tree
Hide file tree
Showing 5 changed files with 1,475 additions and 122 deletions.
15 changes: 11 additions & 4 deletions franka_description/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,10 @@
This folder contains a drake-compatible model of the Franka Emika Panda arm.

The model differs from the original ROS model and the real robot. Notably, in
this model link 5 has been split into lower and upper sections to improve the
ability to filter collisions around the wrist. In this model of the hand, the
fingers are independently actuated, rather than using <mimic> tag, which Drake
does not yet fully support.
this the "link5split" flavor of the model, link 5 has been split into lower and
upper sections to improve the ability to filter collisions around the wrist. In
all flavors of the hand, the fingers are independently actuated, rather than
using <mimic> tag, which Drake does not yet fully support.

In addition, some tags unsupported by Drake have been removed, to reduce the
burden of warning output. For URDF support details, see:
Expand Down Expand Up @@ -46,6 +46,13 @@ https://frankaemika.github.io/docs/control_parameters.html#limits-for-panda

### Collision Filters

#### normal flavor

There is collision filtering applied to ignore collisions between `(panda_link5,
panda_link7)` and between `(panda_link6, panda_link8)`.

#### link5split flavor

The following collision filter groups are defined, all of which filter
collisions within their own group:
- Links 0, 1, 2, and 3 (`group_link0123`)
Expand Down
84 changes: 25 additions & 59 deletions franka_description/urdf/panda_arm.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -326,7 +326,7 @@
<axis xyz="0 0 1"/>
<limit effort="87" lower="-3.0718" upper="-0.0698" velocity="2.1750" drake:acceleration="12.5"/>
</joint>
<link name="panda_link5_lower">
<link name="panda_link5">
<inertial>
<mass value="2.74"/>
<origin xyz="0 0.0610427 -0.104176" rpy="0 0 0"/>
Expand All @@ -350,6 +350,12 @@
<sphere radius="0.06"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0.0 0.09 -0.055"/>
<geometry>
<sphere radius="0.035"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0.0 0.0850 -0.08"/>
<geometry>
Expand Down Expand Up @@ -381,49 +387,36 @@
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0.0 0.05 -0.20"/>
<geometry>
<sphere radius="0.055"/>
</geometry>
</collision>
</link>
<joint name="panda_joint5" type="revolute">
<origin rpy="-1.57079632679 0 0" xyz="-0.0825 0.384 0"/>
<parent link="panda_link4"/>
<child link="panda_link5_lower"/>
<axis xyz="0 0 1"/>
<limit effort="12" lower="-2.8973" upper="2.8973" velocity="2.610" drake:acceleration="15.0"/>
</joint>
<link name="panda_link5_upper">
<collision>
<origin rpy="0 0 0" xyz="0.0 0.09 -0.055"/>
<origin rpy="0 0 0" xyz="0.0 0.08 -0.02"/>
<geometry>
<sphere radius="0.035"/>
<sphere radius="0.05"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0.0 0.08 -0.02"/>
<origin rpy="0 0 0" xyz="0.0 0.08 -0.0"/>
<geometry>
<sphere radius="0.05"/>
<sphere radius="0.055"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0.0 0.08 0.0"/>
<origin rpy="0 0 0" xyz="0.0 0.05 -0.20"/>
<geometry>
<sphere radius="0.055"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0.0 0.07 0.0"/>
<origin rpy="0 0 0" xyz="0.0 0.07 -0.0"/>
<geometry>
<sphere radius="0.06"/>
</geometry>
</collision>
</link>
<joint name="panda_joint5_lower_upper" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="panda_link5_lower"/>
<child link="panda_link5_upper"/>
<joint name="panda_joint5" type="revolute">
<origin rpy="-1.57079632679 0 0" xyz="-0.0825 0.384 0"/>
<parent link="panda_link4"/>
<child link="panda_link5"/>
<axis xyz="0 0 1"/>
<limit effort="12" lower="-2.8973" upper="2.8973" velocity="2.610" drake:acceleration="15.0"/>
</joint>
<link name="panda_link6">
<inertial>
Expand Down Expand Up @@ -470,7 +463,7 @@
</link>
<joint name="panda_joint6" type="revolute">
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<parent link="panda_link5_upper"/>
<parent link="panda_link5"/>
<child link="panda_link6"/>
<axis xyz="0 0 1"/>
<limit effort="12" lower="-0.0175" upper="3.7525" velocity="2.610" drake:acceleration="20.0"/>
Expand Down Expand Up @@ -604,41 +597,14 @@
<drake:rotor_inertia value="0.0000205544064" />
</actuator>
</transmission>
<drake:collision_filter_group name="group_link0123">
<drake:member link="panda_link0"/>
<drake:member link="panda_link1"/>
<drake:member link="panda_link2"/>
<drake:member link="panda_link3"/>
<drake:ignored_collision_filter_group name="group_link0123"/>
</drake:collision_filter_group>
<drake:collision_filter_group name="group_link1234">
<drake:member link="panda_link1"/>
<drake:member link="panda_link2"/>
<drake:member link="panda_link3"/>
<drake:member link="panda_link4"/>
<drake:ignored_collision_filter_group name="group_link1234"/>
</drake:collision_filter_group>
<!-- TODO(calderpg-tri) See if this group could be extended to 345678. -->
<drake:collision_filter_group name="group_link3456">
<drake:member link="panda_link3"/>
<drake:member link="panda_link4"/>
<drake:member link="panda_link5_lower"/>
<drake:member link="panda_link5_upper"/>
<drake:member link="panda_link6"/>
<drake:ignored_collision_filter_group name="group_link3456"/>
</drake:collision_filter_group>
<drake:collision_filter_group name="group_link567">
<drake:member link="panda_link5_lower"/>
<drake:member link="panda_link5_upper"/>
<drake:member link="panda_link6"/>
<drake:collision_filter_group name="group_link57">
<drake:member link="panda_link5"/>
<drake:member link="panda_link7"/>
<drake:ignored_collision_filter_group name="group_link567"/>
<drake:ignored_collision_filter_group name="group_link57"/>
</drake:collision_filter_group>
<drake:collision_filter_group name="group_link5upper678">
<drake:member link="panda_link5_upper"/>
<drake:collision_filter_group name="group_link68">
<drake:member link="panda_link6"/>
<drake:member link="panda_link7"/>
<drake:member link="panda_link8"/>
<drake:ignored_collision_filter_group name="group_link5upper678"/>
<drake:ignored_collision_filter_group name="group_link68"/>
</drake:collision_filter_group>
</robot>
84 changes: 25 additions & 59 deletions franka_description/urdf/panda_arm_hand.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -326,7 +326,7 @@
<axis xyz="0 0 1"/>
<limit effort="87" lower="-3.0718" upper="-0.0698" velocity="2.1750" drake:acceleration="12.5"/>
</joint>
<link name="panda_link5_lower">
<link name="panda_link5">
<inertial>
<mass value="2.74"/>
<origin xyz="0 0.0610427 -0.104176" rpy="0 0 0"/>
Expand All @@ -350,6 +350,12 @@
<sphere radius="0.06"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0.0 0.09 -0.055"/>
<geometry>
<sphere radius="0.035"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0.0 0.0850 -0.08"/>
<geometry>
Expand Down Expand Up @@ -381,49 +387,36 @@
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0.0 0.05 -0.20"/>
<geometry>
<sphere radius="0.055"/>
</geometry>
</collision>
</link>
<joint name="panda_joint5" type="revolute">
<origin rpy="-1.57079632679 0 0" xyz="-0.0825 0.384 0"/>
<parent link="panda_link4"/>
<child link="panda_link5_lower"/>
<axis xyz="0 0 1"/>
<limit effort="12" lower="-2.8973" upper="2.8973" velocity="2.610" drake:acceleration="15.0"/>
</joint>
<link name="panda_link5_upper">
<collision>
<origin rpy="0 0 0" xyz="0.0 0.09 -0.055"/>
<origin rpy="0 0 0" xyz="0.0 0.08 -0.02"/>
<geometry>
<sphere radius="0.035"/>
<sphere radius="0.05"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0.0 0.08 -0.02"/>
<origin rpy="0 0 0" xyz="0.0 0.08 -0.0"/>
<geometry>
<sphere radius="0.05"/>
<sphere radius="0.055"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0.0 0.08 0.0"/>
<origin rpy="0 0 0" xyz="0.0 0.05 -0.20"/>
<geometry>
<sphere radius="0.055"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0.0 0.07 0.0"/>
<origin rpy="0 0 0" xyz="0.0 0.07 -0.0"/>
<geometry>
<sphere radius="0.06"/>
</geometry>
</collision>
</link>
<joint name="panda_joint5_lower_upper" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="panda_link5_lower"/>
<child link="panda_link5_upper"/>
<joint name="panda_joint5" type="revolute">
<origin rpy="-1.57079632679 0 0" xyz="-0.0825 0.384 0"/>
<parent link="panda_link4"/>
<child link="panda_link5"/>
<axis xyz="0 0 1"/>
<limit effort="12" lower="-2.8973" upper="2.8973" velocity="2.610" drake:acceleration="15.0"/>
</joint>
<link name="panda_link6">
<inertial>
Expand Down Expand Up @@ -470,7 +463,7 @@
</link>
<joint name="panda_joint6" type="revolute">
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<parent link="panda_link5_upper"/>
<parent link="panda_link5"/>
<child link="panda_link6"/>
<axis xyz="0 0 1"/>
<limit effort="12" lower="-0.0175" upper="3.7525" velocity="2.610" drake:acceleration="20.0"/>
Expand Down Expand Up @@ -730,41 +723,14 @@
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<drake:collision_filter_group name="group_link0123">
<drake:member link="panda_link0"/>
<drake:member link="panda_link1"/>
<drake:member link="panda_link2"/>
<drake:member link="panda_link3"/>
<drake:ignored_collision_filter_group name="group_link0123"/>
</drake:collision_filter_group>
<drake:collision_filter_group name="group_link1234">
<drake:member link="panda_link1"/>
<drake:member link="panda_link2"/>
<drake:member link="panda_link3"/>
<drake:member link="panda_link4"/>
<drake:ignored_collision_filter_group name="group_link1234"/>
</drake:collision_filter_group>
<!-- TODO(calderpg-tri) See if this group could be extended to 345678. -->
<drake:collision_filter_group name="group_link3456">
<drake:member link="panda_link3"/>
<drake:member link="panda_link4"/>
<drake:member link="panda_link5_lower"/>
<drake:member link="panda_link5_upper"/>
<drake:member link="panda_link6"/>
<drake:ignored_collision_filter_group name="group_link3456"/>
</drake:collision_filter_group>
<drake:collision_filter_group name="group_link567">
<drake:member link="panda_link5_lower"/>
<drake:member link="panda_link5_upper"/>
<drake:member link="panda_link6"/>
<drake:collision_filter_group name="group_link57">
<drake:member link="panda_link5"/>
<drake:member link="panda_link7"/>
<drake:ignored_collision_filter_group name="group_link567"/>
<drake:ignored_collision_filter_group name="group_link57"/>
</drake:collision_filter_group>
<drake:collision_filter_group name="group_link5upper678">
<drake:member link="panda_link5_upper"/>
<drake:collision_filter_group name="group_link68">
<drake:member link="panda_link6"/>
<drake:member link="panda_link7"/>
<drake:member link="panda_link8"/>
<drake:ignored_collision_filter_group name="group_link5upper678"/>
<drake:ignored_collision_filter_group name="group_link68"/>
</drake:collision_filter_group>
</robot>
Loading

0 comments on commit 11e0cc1

Please sign in to comment.