Skip to content

Commit

Permalink
create xacro macro for wheel
Browse files Browse the repository at this point in the history
Signed-off-by: Autumn60 <[email protected]>
  • Loading branch information
Autumn60 committed Aug 30, 2024
1 parent 1911b65 commit c864d7c
Show file tree
Hide file tree
Showing 2 changed files with 29 additions and 26 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:property name="robot_info" value="${xacro.load_yaml('$(find fourth_robot_description)/config/robot_info.param.yaml')}"/>

<xacro:include filename="$(find fourth_robot_description)/urdf/wheel/wheel.urdf.xacro"/>

<link name="base_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
Expand All @@ -18,31 +20,11 @@
<origin xyz="0 0 -${robot_info['/**']['ros__parameters']['wheel_radius']}" rpy="0 0 0"/>
</joint>

<link name="wheel_left_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://fourth_robot_description/mesh/wheel/wheel.dae" scale="1 1 1"/>
</geometry>
</visual>
</link>
<joint name="wheel_left_joint" type="fixed">
<parent link="base_link"/>
<child link="wheel_left_link"/>
<origin xyz="0 -${robot_info['/**']['ros__parameters']['wheel_tread'] / 2} 0" rpy="0 0 0"/>
</joint>
<xacro:wheel name="wheel_left" parent="base_link" wheel_radius="${robot_info['/**']['ros__parameters']['wheel_radius']}">
<origin xyz="0 ${robot_info['/**']['ros__parameters']['wheel_tread'] / 2} 0" rpy="0 0 0"/>
</xacro:wheel>

<link name="wheel_right_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://fourth_robot_description/mesh/wheel/wheel.dae" scale="1 1 1"/>
</geometry>
</visual>
</link>
<joint name="wheel_right_joint" type="fixed">
<parent link="base_link"/>
<child link="wheel_right_link"/>
<origin xyz="0 ${robot_info['/**']['ros__parameters']['wheel_tread'] / 2} 0" rpy="0 0 ${pi}"/>
</joint>
<xacro:wheel name="wheel_right" parent="base_link" wheel_radius="${robot_info['/**']['ros__parameters']['wheel_radius']}">
<origin xyz="0 -${robot_info['/**']['ros__parameters']['wheel_tread'] / 2} 0" rpy="0 0 ${pi}"/>
</xacro:wheel>
</robot>
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:property name="model_wheel_radius" value="0.193125"/>

<xacro:macro name="wheel" params="name parent wheel_radius *joint_origin">
<link name="${name}_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://fourth_robot_description/mesh/wheel/wheel.dae" scale="${wheel_radius / model_wheel_radius} 1 ${wheel_radius / model_wheel_radius}"/>
</geometry>
</visual>
</link>

<joint name="${name}_joint" type="fixed">
<xacro:insert_block name="joint_origin"/>
<parent link="${parent}"/>
<child link="${name}_link"/>
</joint>
</xacro:macro>
</robot>

0 comments on commit c864d7c

Please sign in to comment.