Skip to content

Commit 11e0cc1

Browse files
authored
Move split link5 into different filename (#75)
Revert the changes to panda_arm{,_hand}.urdf. Instead, copy the changes to new files named link5split.
1 parent 6b67e4c commit 11e0cc1

File tree

5 files changed

+1475
-122
lines changed

5 files changed

+1475
-122
lines changed

franka_description/README.md

Lines changed: 11 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -3,10 +3,10 @@
33
This folder contains a drake-compatible model of the Franka Emika Panda arm.
44

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

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

4747
### Collision Filters
4848

49+
#### normal flavor
50+
51+
There is collision filtering applied to ignore collisions between `(panda_link5,
52+
panda_link7)` and between `(panda_link6, panda_link8)`.
53+
54+
#### link5split flavor
55+
4956
The following collision filter groups are defined, all of which filter
5057
collisions within their own group:
5158
- Links 0, 1, 2, and 3 (`group_link0123`)

franka_description/urdf/panda_arm.urdf

Lines changed: 25 additions & 59 deletions
Original file line numberDiff line numberDiff line change
@@ -326,7 +326,7 @@
326326
<axis xyz="0 0 1"/>
327327
<limit effort="87" lower="-3.0718" upper="-0.0698" velocity="2.1750" drake:acceleration="12.5"/>
328328
</joint>
329-
<link name="panda_link5_lower">
329+
<link name="panda_link5">
330330
<inertial>
331331
<mass value="2.74"/>
332332
<origin xyz="0 0.0610427 -0.104176" rpy="0 0 0"/>
@@ -350,6 +350,12 @@
350350
<sphere radius="0.06"/>
351351
</geometry>
352352
</collision>
353+
<collision>
354+
<origin rpy="0 0 0" xyz="0.0 0.09 -0.055"/>
355+
<geometry>
356+
<sphere radius="0.035"/>
357+
</geometry>
358+
</collision>
353359
<collision>
354360
<origin rpy="0 0 0" xyz="0.0 0.0850 -0.08"/>
355361
<geometry>
@@ -381,49 +387,36 @@
381387
</geometry>
382388
</collision>
383389
<collision>
384-
<origin rpy="0 0 0" xyz="0.0 0.05 -0.20"/>
385-
<geometry>
386-
<sphere radius="0.055"/>
387-
</geometry>
388-
</collision>
389-
</link>
390-
<joint name="panda_joint5" type="revolute">
391-
<origin rpy="-1.57079632679 0 0" xyz="-0.0825 0.384 0"/>
392-
<parent link="panda_link4"/>
393-
<child link="panda_link5_lower"/>
394-
<axis xyz="0 0 1"/>
395-
<limit effort="12" lower="-2.8973" upper="2.8973" velocity="2.610" drake:acceleration="15.0"/>
396-
</joint>
397-
<link name="panda_link5_upper">
398-
<collision>
399-
<origin rpy="0 0 0" xyz="0.0 0.09 -0.055"/>
390+
<origin rpy="0 0 0" xyz="0.0 0.08 -0.02"/>
400391
<geometry>
401-
<sphere radius="0.035"/>
392+
<sphere radius="0.05"/>
402393
</geometry>
403394
</collision>
404395
<collision>
405-
<origin rpy="0 0 0" xyz="0.0 0.08 -0.02"/>
396+
<origin rpy="0 0 0" xyz="0.0 0.08 -0.0"/>
406397
<geometry>
407-
<sphere radius="0.05"/>
398+
<sphere radius="0.055"/>
408399
</geometry>
409400
</collision>
410401
<collision>
411-
<origin rpy="0 0 0" xyz="0.0 0.08 0.0"/>
402+
<origin rpy="0 0 0" xyz="0.0 0.05 -0.20"/>
412403
<geometry>
413404
<sphere radius="0.055"/>
414405
</geometry>
415406
</collision>
416407
<collision>
417-
<origin rpy="0 0 0" xyz="0.0 0.07 0.0"/>
408+
<origin rpy="0 0 0" xyz="0.0 0.07 -0.0"/>
418409
<geometry>
419410
<sphere radius="0.06"/>
420411
</geometry>
421412
</collision>
422413
</link>
423-
<joint name="panda_joint5_lower_upper" type="fixed">
424-
<origin rpy="0 0 0" xyz="0 0 0"/>
425-
<parent link="panda_link5_lower"/>
426-
<child link="panda_link5_upper"/>
414+
<joint name="panda_joint5" type="revolute">
415+
<origin rpy="-1.57079632679 0 0" xyz="-0.0825 0.384 0"/>
416+
<parent link="panda_link4"/>
417+
<child link="panda_link5"/>
418+
<axis xyz="0 0 1"/>
419+
<limit effort="12" lower="-2.8973" upper="2.8973" velocity="2.610" drake:acceleration="15.0"/>
427420
</joint>
428421
<link name="panda_link6">
429422
<inertial>
@@ -470,7 +463,7 @@
470463
</link>
471464
<joint name="panda_joint6" type="revolute">
472465
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
473-
<parent link="panda_link5_upper"/>
466+
<parent link="panda_link5"/>
474467
<child link="panda_link6"/>
475468
<axis xyz="0 0 1"/>
476469
<limit effort="12" lower="-0.0175" upper="3.7525" velocity="2.610" drake:acceleration="20.0"/>
@@ -604,41 +597,14 @@
604597
<drake:rotor_inertia value="0.0000205544064" />
605598
</actuator>
606599
</transmission>
607-
<drake:collision_filter_group name="group_link0123">
608-
<drake:member link="panda_link0"/>
609-
<drake:member link="panda_link1"/>
610-
<drake:member link="panda_link2"/>
611-
<drake:member link="panda_link3"/>
612-
<drake:ignored_collision_filter_group name="group_link0123"/>
613-
</drake:collision_filter_group>
614-
<drake:collision_filter_group name="group_link1234">
615-
<drake:member link="panda_link1"/>
616-
<drake:member link="panda_link2"/>
617-
<drake:member link="panda_link3"/>
618-
<drake:member link="panda_link4"/>
619-
<drake:ignored_collision_filter_group name="group_link1234"/>
620-
</drake:collision_filter_group>
621-
<!-- TODO(calderpg-tri) See if this group could be extended to 345678. -->
622-
<drake:collision_filter_group name="group_link3456">
623-
<drake:member link="panda_link3"/>
624-
<drake:member link="panda_link4"/>
625-
<drake:member link="panda_link5_lower"/>
626-
<drake:member link="panda_link5_upper"/>
627-
<drake:member link="panda_link6"/>
628-
<drake:ignored_collision_filter_group name="group_link3456"/>
629-
</drake:collision_filter_group>
630-
<drake:collision_filter_group name="group_link567">
631-
<drake:member link="panda_link5_lower"/>
632-
<drake:member link="panda_link5_upper"/>
633-
<drake:member link="panda_link6"/>
600+
<drake:collision_filter_group name="group_link57">
601+
<drake:member link="panda_link5"/>
634602
<drake:member link="panda_link7"/>
635-
<drake:ignored_collision_filter_group name="group_link567"/>
603+
<drake:ignored_collision_filter_group name="group_link57"/>
636604
</drake:collision_filter_group>
637-
<drake:collision_filter_group name="group_link5upper678">
638-
<drake:member link="panda_link5_upper"/>
605+
<drake:collision_filter_group name="group_link68">
639606
<drake:member link="panda_link6"/>
640-
<drake:member link="panda_link7"/>
641607
<drake:member link="panda_link8"/>
642-
<drake:ignored_collision_filter_group name="group_link5upper678"/>
608+
<drake:ignored_collision_filter_group name="group_link68"/>
643609
</drake:collision_filter_group>
644610
</robot>

franka_description/urdf/panda_arm_hand.urdf

Lines changed: 25 additions & 59 deletions
Original file line numberDiff line numberDiff line change
@@ -326,7 +326,7 @@
326326
<axis xyz="0 0 1"/>
327327
<limit effort="87" lower="-3.0718" upper="-0.0698" velocity="2.1750" drake:acceleration="12.5"/>
328328
</joint>
329-
<link name="panda_link5_lower">
329+
<link name="panda_link5">
330330
<inertial>
331331
<mass value="2.74"/>
332332
<origin xyz="0 0.0610427 -0.104176" rpy="0 0 0"/>
@@ -350,6 +350,12 @@
350350
<sphere radius="0.06"/>
351351
</geometry>
352352
</collision>
353+
<collision>
354+
<origin rpy="0 0 0" xyz="0.0 0.09 -0.055"/>
355+
<geometry>
356+
<sphere radius="0.035"/>
357+
</geometry>
358+
</collision>
353359
<collision>
354360
<origin rpy="0 0 0" xyz="0.0 0.0850 -0.08"/>
355361
<geometry>
@@ -381,49 +387,36 @@
381387
</geometry>
382388
</collision>
383389
<collision>
384-
<origin rpy="0 0 0" xyz="0.0 0.05 -0.20"/>
385-
<geometry>
386-
<sphere radius="0.055"/>
387-
</geometry>
388-
</collision>
389-
</link>
390-
<joint name="panda_joint5" type="revolute">
391-
<origin rpy="-1.57079632679 0 0" xyz="-0.0825 0.384 0"/>
392-
<parent link="panda_link4"/>
393-
<child link="panda_link5_lower"/>
394-
<axis xyz="0 0 1"/>
395-
<limit effort="12" lower="-2.8973" upper="2.8973" velocity="2.610" drake:acceleration="15.0"/>
396-
</joint>
397-
<link name="panda_link5_upper">
398-
<collision>
399-
<origin rpy="0 0 0" xyz="0.0 0.09 -0.055"/>
390+
<origin rpy="0 0 0" xyz="0.0 0.08 -0.02"/>
400391
<geometry>
401-
<sphere radius="0.035"/>
392+
<sphere radius="0.05"/>
402393
</geometry>
403394
</collision>
404395
<collision>
405-
<origin rpy="0 0 0" xyz="0.0 0.08 -0.02"/>
396+
<origin rpy="0 0 0" xyz="0.0 0.08 -0.0"/>
406397
<geometry>
407-
<sphere radius="0.05"/>
398+
<sphere radius="0.055"/>
408399
</geometry>
409400
</collision>
410401
<collision>
411-
<origin rpy="0 0 0" xyz="0.0 0.08 0.0"/>
402+
<origin rpy="0 0 0" xyz="0.0 0.05 -0.20"/>
412403
<geometry>
413404
<sphere radius="0.055"/>
414405
</geometry>
415406
</collision>
416407
<collision>
417-
<origin rpy="0 0 0" xyz="0.0 0.07 0.0"/>
408+
<origin rpy="0 0 0" xyz="0.0 0.07 -0.0"/>
418409
<geometry>
419410
<sphere radius="0.06"/>
420411
</geometry>
421412
</collision>
422413
</link>
423-
<joint name="panda_joint5_lower_upper" type="fixed">
424-
<origin rpy="0 0 0" xyz="0 0 0"/>
425-
<parent link="panda_link5_lower"/>
426-
<child link="panda_link5_upper"/>
414+
<joint name="panda_joint5" type="revolute">
415+
<origin rpy="-1.57079632679 0 0" xyz="-0.0825 0.384 0"/>
416+
<parent link="panda_link4"/>
417+
<child link="panda_link5"/>
418+
<axis xyz="0 0 1"/>
419+
<limit effort="12" lower="-2.8973" upper="2.8973" velocity="2.610" drake:acceleration="15.0"/>
427420
</joint>
428421
<link name="panda_link6">
429422
<inertial>
@@ -470,7 +463,7 @@
470463
</link>
471464
<joint name="panda_joint6" type="revolute">
472465
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
473-
<parent link="panda_link5_upper"/>
466+
<parent link="panda_link5"/>
474467
<child link="panda_link6"/>
475468
<axis xyz="0 0 1"/>
476469
<limit effort="12" lower="-0.0175" upper="3.7525" velocity="2.610" drake:acceleration="20.0"/>
@@ -730,41 +723,14 @@
730723
<mechanicalReduction>1</mechanicalReduction>
731724
</actuator>
732725
</transmission>
733-
<drake:collision_filter_group name="group_link0123">
734-
<drake:member link="panda_link0"/>
735-
<drake:member link="panda_link1"/>
736-
<drake:member link="panda_link2"/>
737-
<drake:member link="panda_link3"/>
738-
<drake:ignored_collision_filter_group name="group_link0123"/>
739-
</drake:collision_filter_group>
740-
<drake:collision_filter_group name="group_link1234">
741-
<drake:member link="panda_link1"/>
742-
<drake:member link="panda_link2"/>
743-
<drake:member link="panda_link3"/>
744-
<drake:member link="panda_link4"/>
745-
<drake:ignored_collision_filter_group name="group_link1234"/>
746-
</drake:collision_filter_group>
747-
<!-- TODO(calderpg-tri) See if this group could be extended to 345678. -->
748-
<drake:collision_filter_group name="group_link3456">
749-
<drake:member link="panda_link3"/>
750-
<drake:member link="panda_link4"/>
751-
<drake:member link="panda_link5_lower"/>
752-
<drake:member link="panda_link5_upper"/>
753-
<drake:member link="panda_link6"/>
754-
<drake:ignored_collision_filter_group name="group_link3456"/>
755-
</drake:collision_filter_group>
756-
<drake:collision_filter_group name="group_link567">
757-
<drake:member link="panda_link5_lower"/>
758-
<drake:member link="panda_link5_upper"/>
759-
<drake:member link="panda_link6"/>
726+
<drake:collision_filter_group name="group_link57">
727+
<drake:member link="panda_link5"/>
760728
<drake:member link="panda_link7"/>
761-
<drake:ignored_collision_filter_group name="group_link567"/>
729+
<drake:ignored_collision_filter_group name="group_link57"/>
762730
</drake:collision_filter_group>
763-
<drake:collision_filter_group name="group_link5upper678">
764-
<drake:member link="panda_link5_upper"/>
731+
<drake:collision_filter_group name="group_link68">
765732
<drake:member link="panda_link6"/>
766-
<drake:member link="panda_link7"/>
767733
<drake:member link="panda_link8"/>
768-
<drake:ignored_collision_filter_group name="group_link5upper678"/>
734+
<drake:ignored_collision_filter_group name="group_link68"/>
769735
</drake:collision_filter_group>
770736
</robot>

0 commit comments

Comments
 (0)