Skip to content

Commit 04f0268

Browse files
committed
CHANGE: Rename xacro:{link_detailed_coarse -> link_with_sc}
The name "detailed_coarse" is a bit contradicting. More suitable might be a name which indicates that existing `<link>`s are augmented with additional functionality such as self-collision geometries. This in mind it also should also be rather consise so I went with `link_with_sc`.
1 parent 1ac7f18 commit 04f0268

File tree

3 files changed

+20
-19
lines changed

3 files changed

+20
-19
lines changed

franka_description/robots/hand.xacro

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -10,12 +10,12 @@
1010
</joint>
1111
</xacro:unless>
1212

13-
<xacro:link_detailed_coarse name="hand">
13+
<xacro:link_with_sc name="hand">
1414
<self_collision_geometries>
1515
<xacro:collision_capsule xyz="0 0 0.04" direction="y" radius="${0.04+safety_distance}" length="0.1" />
1616
<xacro:collision_capsule xyz="0 0 0.10" direction="y" radius="${0.02+safety_distance}" length="0.1" />
1717
</self_collision_geometries>
18-
</xacro:link_detailed_coarse>
18+
</xacro:link_with_sc>
1919

2020
<!-- Define the hand_tcp frame -->
2121
<link name="${arm_id}_hand_tcp" />

franka_description/robots/panda_arm.xacro

Lines changed: 16 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -11,17 +11,17 @@
1111
</joint>
1212
</xacro:unless>
1313

14-
<xacro:link_detailed_coarse name="link0">
14+
<xacro:link_with_sc name="link0">
1515
<self_collision_geometries>
1616
<xacro:collision_capsule xyz="-0.075 0 0.06" direction="x" radius="${0.06+safety_distance}" length="0.03" />
1717
</self_collision_geometries>
18-
</xacro:link_detailed_coarse>
18+
</xacro:link_with_sc>
1919

20-
<xacro:link_detailed_coarse name="link1">
20+
<xacro:link_with_sc name="link1">
2121
<self_collision_geometries>
2222
<xacro:collision_capsule xyz="0 0 -191.5e-3" radius="${0.06+safety_distance}" length="0.283" />
2323
</self_collision_geometries>
24-
</xacro:link_detailed_coarse>
24+
</xacro:link_with_sc>
2525

2626
<joint name="${arm_id}_joint1" type="revolute">
2727
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973" />
@@ -33,11 +33,11 @@
3333
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16" />
3434
</joint>
3535

36-
<xacro:link_detailed_coarse name="link2">
36+
<xacro:link_with_sc name="link2">
3737
<self_collision_geometries>
3838
<xacro:collision_capsule xyz="0 0 0" radius="${0.06+safety_distance}" length="0.12" />
3939
</self_collision_geometries>
40-
</xacro:link_detailed_coarse>
40+
</xacro:link_with_sc>
4141

4242
<joint name="${arm_id}_joint2" type="revolute">
4343
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-1.7628" soft_upper_limit="1.7628" />
@@ -49,11 +49,11 @@
4949
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16" />
5050
</joint>
5151

52-
<xacro:link_detailed_coarse name="link3">
52+
<xacro:link_with_sc name="link3">
5353
<self_collision_geometries>
5454
<xacro:collision_capsule xyz="0 0 -0.145" radius="${0.06+safety_distance}" length="0.15" />
5555
</self_collision_geometries>
56-
</xacro:link_detailed_coarse>
56+
</xacro:link_with_sc>
5757

5858
<joint name="${arm_id}_joint3" type="revolute">
5959
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973" />
@@ -65,11 +65,11 @@
6565
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16" />
6666
</joint>
6767

68-
<xacro:link_detailed_coarse name="link4">
68+
<xacro:link_with_sc name="link4">
6969
<self_collision_geometries>
7070
<xacro:collision_capsule xyz="0 0 0" radius="${0.06+safety_distance}" length="0.12" />
7171
</self_collision_geometries>
72-
</xacro:link_detailed_coarse>
72+
</xacro:link_with_sc>
7373

7474
<joint name="${arm_id}_joint4" type="revolute">
7575
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-3.0718" soft_upper_limit="-0.0698" />
@@ -81,12 +81,12 @@
8181
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16" />
8282
</joint>
8383

84-
<xacro:link_detailed_coarse name="link5">
84+
<xacro:link_with_sc name="link5">
8585
<self_collision_geometries>
8686
<xacro:collision_capsule xyz="0 0 -0.26" radius="${0.060+safety_distance}" length="0.10" />
8787
<xacro:collision_capsule xyz="0 0.08 -0.13" radius="${0.025+safety_distance}" length="0.14" />
8888
</self_collision_geometries>
89-
</xacro:link_detailed_coarse>
89+
</xacro:link_with_sc>
9090

9191
<joint name="${arm_id}_joint5" type="revolute">
9292
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973" />
@@ -98,11 +98,11 @@
9898
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16" />
9999
</joint>
100100

101-
<xacro:link_detailed_coarse name="link6">
101+
<xacro:link_with_sc name="link6">
102102
<self_collision_geometries>
103103
<xacro:collision_capsule xyz="0 0 -0.03" radius="${0.05+safety_distance}" length="0.08" />
104104
</self_collision_geometries>
105-
</xacro:link_detailed_coarse>
105+
</xacro:link_with_sc>
106106

107107
<joint name="${arm_id}_joint6" type="revolute">
108108
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-0.0175" soft_upper_limit="3.7525" />
@@ -114,12 +114,12 @@
114114
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16" />
115115
</joint>
116116

117-
<xacro:link_detailed_coarse name="link7" rpy="0 0 ${pi/4}">
117+
<xacro:link_with_sc name="link7" rpy="0 0 ${pi/4}">
118118
<self_collision_geometries>
119119
<xacro:collision_capsule xyz="0 0 0.01" direction="z" radius="${0.04+safety_distance}" length="0.14" />
120120
<xacro:collision_capsule xyz="0.06 0 0.082" direction="x" radius="${0.03+safety_distance}" length="0.01" />
121121
</self_collision_geometries>
122-
</xacro:link_detailed_coarse>
122+
</xacro:link_with_sc>
123123

124124
<joint name="${arm_id}_joint7" type="revolute">
125125
<safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>

franka_description/robots/utils.xacro

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -26,12 +26,13 @@
2626
<!-- Macro to add a single link, both with -->
2727
<!-- * detailed meshes for environmental collision checking -->
2828
<!-- * and coarse geometry models for self-collision checking -->
29+
<!-- (only if 'gazebo' arg is set) -->
2930
<!-- -->
3031
<!-- name: Name of the robot link (without prefix) -->
3132
<!-- rpy: Rotation of the *_sc link relative to parent [rad] -->
3233
<!-- self_collision_geometries: self <collision> models -->
3334
<!-- ========================================================== -->
34-
<xacro:macro name="link_detailed_coarse" params="name prefix=${arm_id}_ rpy:='0 0 0' **self_collision_geometries">
35+
<xacro:macro name="link_with_sc" params="name prefix=${arm_id}_ rpy:='0 0 0' **self_collision_geometries">
3536
<!-- sub-link defining detailed meshes for collision with environment -->
3637
<link name="${prefix}${name}">
3738
<visual>

0 commit comments

Comments
 (0)