Skip to content

Commit

Permalink
Simplify if-else clauses
Browse files Browse the repository at this point in the history
Improve extensibility (adding more sensors) by emloying an exclusive-if-and-final-else
strategy, utilizing a helper variable. This way we avoid augmenting the list in the
'sensor in [...]' tests.
  • Loading branch information
rhaschke committed Oct 4, 2021
1 parent ef82347 commit a8fecfa
Show file tree
Hide file tree
Showing 3 changed files with 49 additions and 39 deletions.
55 changes: 29 additions & 26 deletions sr_description/hand/xacro/finger/distal/distal.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -25,44 +25,47 @@ xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="${prefix}${link_prefix}distal_visual">
<xacro:unless value="${tip_sensor in ['bt_sp','eli']}">
<!-- Standard distal -->
<mesh filename="package://sr_description/meshes/hand/F1.dae"
<!-- Do we need to instantiate the standard distal? -->
<xacro:property name="standard" value="true" />
<xacro:if value="${tip_sensor == 'eli'}">
<!-- Ellispoid distal -->
<mesh filename="package://sr_description/meshes/hand/ellipsoids/distal_ellipsoid_visual.dae"
scale="0.001 0.001 0.001" />
</xacro:unless>
<xacro:if value="${tip_sensor in ['bt_sp','eli']}">
<xacro:if value="${tip_sensor == 'eli'}">
<!-- Ellispoid distal -->
<mesh filename="package://sr_description/meshes/hand/ellipsoids/distal_ellipsoid_visual.dae"
scale="0.001 0.001 0.001" />
</xacro:if>
<xacro:if value="${tip_sensor == 'bt_sp'}">
<!-- bt_sp distal -->
<mesh filename="package://sr_description/meshes/hand/biotacs/sp.dae" />
</xacro:if>
<xacro:property name="standard" value="false" />
</xacro:if>
<xacro:if value="${tip_sensor == 'bt_sp'}">
<!-- bt_sp distal -->
<mesh filename="package://sr_description/meshes/hand/biotacs/sp.dae" />
<xacro:property name="standard" value="false" />
</xacro:if>
<xacro:if value="${standard}">
<!-- Standard distal -->
<mesh filename="package://sr_description/meshes/hand/F1.dae" scale="0.001 0.001 0.001" />
</xacro:if>
</geometry>
<!-- <material name="Grey" /> -->
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="${prefix}${link_prefix}distal_collision_geom">
<xacro:if value="${tip_sensor in ['bt_sp','eli']}">
<xacro:if value="${tip_sensor == 'eli'}">
<!-- Ellispoid distal -->
<mesh filename="package://sr_description/meshes/hand/ellipsoids/distal_ellipsoid.dae"
scale="0.001 0.001 0.001" />
</xacro:if>
<xacro:if value="${tip_sensor == 'bt_sp'}">
<!-- bt_sp distal -->
<mesh filename="package://sr_description/meshes/hand/biotacs/sp.dae" />
</xacro:if>
<!-- Do we need to instantiate the standard distal? -->
<xacro:property name="standard" value="true" />
<xacro:if value="${tip_sensor == 'eli'}">
<!-- Ellispoid distal -->
<mesh filename="package://sr_description/meshes/hand/ellipsoids/distal_ellipsoid.dae"
scale="0.001 0.001 0.001" />
<xacro:property name="standard" value="false" />
</xacro:if>
<xacro:unless value="${tip_sensor in ['bt_sp','eli']}">
<xacro:if value="${tip_sensor == 'bt_sp'}">
<!-- bt_sp distal -->
<mesh filename="package://sr_description/meshes/hand/biotacs/sp.dae" />
<xacro:property name="standard" value="false" />
</xacro:if>
<xacro:if value="${standard}">
<!-- Standard distal -->
<mesh filename="package://sr_description/meshes/hand/F1.dae"
scale="0.001 0.001 0.001" />
</xacro:unless>
</xacro:if>
</geometry>
</collision>
</link>
Expand Down
2 changes: 1 addition & 1 deletion sr_description/hand/xacro/thumb/thdistal.gazebo.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<xacro:macro name="thdistal_gazebo" params="prefix:=^ tip_sensor:=^|std ns:=^|''">
<!-- prefix can be anything but usually is "r_" or "l_" for right and left hands distinction -->
<gazebo reference="${prefix}thdistal">
<xacro:unless value="${'none' in tip_sensor}" >
<xacro:unless value="${'none' in tip_sensor}" >
<sensor type="contact" name="${prefix}thdistal_contact">
<always_on>1</always_on>
<update_rate>1000.0</update_rate>
Expand Down
31 changes: 19 additions & 12 deletions sr_description/hand/xacro/thumb/thdistal.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -125,19 +125,23 @@ xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="${prefix}thdistal_visual">
<xacro:unless value="${tip_sensor in ['bt_sp','eli']}">
<!-- Standard distal -->
<mesh filename="package://sr_description/meshes/hand/TH1_z.dae"
scale="0.001 0.001 0.001" />
</xacro:unless>
<!-- Do we need to instantiate the standard distal? -->
<xacro:property name="standard" value="true" />
<xacro:if value="${tip_sensor == 'eli'}">
<!-- Ellispoid distal -->
<mesh filename="package://sr_description/meshes/hand/ellipsoids/thdistal_ellipsoid_visual.dae"
scale="0.001 0.001 0.001" />
scale="0.001 0.001 0.001" />
<xacro:property name="standard" value="false" />
</xacro:if>
<xacro:if value="${tip_sensor == 'bt_sp'}">
<!-- bt sp distal -->
<mesh filename="package://sr_description/meshes/hand/biotacs/sp.dae" />
<xacro:property name="standard" value="false" />
</xacro:if>
<xacro:if value="${standard}">
<!-- Standard distal -->
<mesh filename="package://sr_description/meshes/hand/TH1_z.dae"
scale="0.001 0.001 0.001" />
</xacro:if>
</geometry>
<material name="shadow_thmiddle_material">
Expand All @@ -147,19 +151,22 @@ xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom">
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="${prefix}thmiddle_collision_geom">
<xacro:unless value="${tip_sensor in ['bt_sp','eli']}">
<!-- Standard distal -->
<mesh filename="package://sr_description/meshes/hand/TH1_z.dae"
scale="0.001 0.001 0.001" />
</xacro:unless>
<!-- Do we need to instantiate the standard distal? -->
<xacro:property name="standard" value="true" />
<xacro:if value="${tip_sensor == 'eli'}">
<!-- Ellispoid distal -->
<mesh filename="package://sr_description/meshes/hand/ellipsoids/thdistal_ellipsoid.dae"
scale="0.001 0.001 0.001" />
scale="0.001 0.001 0.001" />
<xacro:property name="standard" value="false" />
</xacro:if>
<xacro:if value="${tip_sensor == 'bt_sp'}">
<!-- bt sp distal -->
<mesh filename="package://sr_description/meshes/hand/biotacs/sp.dae" />
<xacro:property name="standard" value="false" />
</xacro:if>
<xacro:if value="${standard}">
<!-- Standard distal -->
<mesh filename="package://sr_description/meshes/hand/TH1_z.dae" scale="0.001 0.001 0.001" />
</xacro:if>
<!-- <box size="0.015 0.015 0.015" /> -->
</geometry>
Expand Down

0 comments on commit a8fecfa

Please sign in to comment.