Skip to content

Commit

Permalink
Add optional parameter to generate Fixed/Coninuous caster joint (#100)
Browse files Browse the repository at this point in the history
Signed-off-by: Christian Barcelo <christianbarcelo@ekumenlabs.com>
  • Loading branch information
BarceloChristian committed Jul 6, 2023
1 parent 83f131c commit 61ce6d9
Show file tree
Hide file tree
Showing 2 changed files with 43 additions and 17 deletions.
2 changes: 2 additions & 0 deletions andino_description/urdf/andino.urdf.xacro
Expand Up @@ -10,6 +10,7 @@

<xacro:property name="caster_wheel_yaml" value="$(find ${package_name})/config/${robot_name}/caster_wheel.yaml" />
<xacro:property name="caster_wheel_props" value="${xacro.load_yaml(caster_wheel_yaml)}"/>
<xacro:arg name="use_fixed_caster" default="True"/>

<xacro:property name="wheel_yaml" value="$(find ${package_name})/config/${robot_name}/wheel.yaml" />
<xacro:property name="wheel_props" value="${xacro.load_yaml(wheel_yaml)}"/>
Expand Down Expand Up @@ -44,6 +45,7 @@

<!-- Caster Wheel -->
<xacro:caster_wheel reflect="-1"
use_fixed="$(arg use_fixed_caster)"
wheel_props="${caster_wheel_props}">
</xacro:caster_wheel>

Expand Down
58 changes: 41 additions & 17 deletions andino_description/urdf/include/andino_caster_macro.urdf.xacro
Expand Up @@ -9,6 +9,7 @@
params:
- reflect [1/-1]: value to set the side of the caster;
- use_fixed [bool]: wheter to use a fixed model or not
- wheel_props [dictionary]: wheel properties;
- base_props [dictionary]: base link properties;
- mesh [string]: file name of the wheel mesh;
Expand All @@ -17,7 +18,7 @@

<!-- Caster wheel link & joint macro -->
<xacro:macro name="caster_wheel"
params="reflect wheel_props locationright:=${0} scale:=''">
params="reflect use_fixed wheel_props locationright:=${0} scale:=''">
<link name="caster_base_link">
<xacro:box_inertia m="${wheel_props['base']['mass']}"
x="${wheel_props['base']['size']['x']}"
Expand Down Expand Up @@ -56,7 +57,7 @@
</collision>
</link>
<joint name="caster_base_joint" type="fixed">
<origin xyz="${wheel_props['base']['dx']} ${-wheel_props['base']['dy'] * locationright} ${wheel_props['base']['dz']}"
<origin xyz="${wheel_props['base']['dx']} ${-wheel_props['base']['dy'] * locationright} ${wheel_props['base']['dz']}"
rpy="0 0 0" />
<parent link="base_link" />
<child link="caster_base_link" />
Expand Down Expand Up @@ -103,14 +104,26 @@
</geometry>
</collision>
</link>
<joint name="caster_rotation_joint" type="fixed">
<origin xyz="${wheel_props['hub']['dx']} ${-wheel_props['hub']['dy'] * locationright} ${wheel_props['hub']['dz']}"
rpy="0 0 0" />
<parent link="base_link" />
<child link="caster_rotation_link" />
<axis xyz="0 0 1" />
<dynamics damping="0.01" friction="0.0"/>
</joint>
<xacro:if value="${use_fixed}">
<joint name="caster_rotation_joint" type="fixed">
<origin xyz="${wheel_props['hub']['dx']} ${-wheel_props['hub']['dy'] * locationright} ${wheel_props['hub']['dz']}"
rpy="0 0 0" />
<parent link="base_link" />
<child link="caster_rotation_link" />
<axis xyz="0 0 1" />
<dynamics damping="0.01" friction="0.0"/>
</joint>
</xacro:if>
<xacro:unless value="${use_fixed}">
<joint name="caster_rotation_joint" type="continuous">
<origin xyz="${wheel_props['hub']['dx']} ${-wheel_props['hub']['dy'] * locationright} ${wheel_props['hub']['dz']}"
rpy="0 0 0" />
<parent link="base_link" />
<child link="caster_rotation_link" />
<axis xyz="0 0 1" />
<dynamics damping="0.01" friction="0.0"/>
</joint>
</xacro:unless>


<!-- caster wheel -->
Expand Down Expand Up @@ -149,13 +162,24 @@
</geometry>
</collision>
</link>
<joint name="caster_wheel_joint" type="fixed">
<origin xyz="${wheel_props['wheel']['dx']} ${-wheel_props['wheel']['dy'] * locationright} ${wheel_props['wheel']['dz']}"
rpy="0 0 0" />
<parent link="caster_rotation_link" />
<child link="caster_wheel_link" />
<axis xyz="0 1 0" />
</joint>
<xacro:if value="${use_fixed}">
<joint name="caster_wheel_joint" type="fixed">
<origin xyz="${wheel_props['wheel']['dx']} ${-wheel_props['wheel']['dy'] * locationright} ${wheel_props['wheel']['dz']}"
rpy="0 0 0" />
<parent link="caster_rotation_link" />
<child link="caster_wheel_link" />
<axis xyz="0 1 0" />
</joint>
</xacro:if>
<xacro:unless value="${use_fixed}">
<joint name="caster_wheel_joint" type="continuous">
<origin xyz="${wheel_props['wheel']['dx']} ${-wheel_props['wheel']['dy'] * locationright} ${wheel_props['wheel']['dz']}"
rpy="0 0 0" />
<parent link="caster_rotation_link" />
<child link="caster_wheel_link" />
<axis xyz="0 1 0" />
</joint>
</xacro:unless>
</xacro:macro>

</robot>

0 comments on commit 61ce6d9

Please sign in to comment.