Skip to content

Instantly share code, notes, and snippets.

@pasindu-sandima
Last active January 12, 2021 06:18
Show Gist options
  • Save pasindu-sandima/10ce1b6412a127da430bc35e2d3210dd to your computer and use it in GitHub Desktop.
Save pasindu-sandima/10ce1b6412a127da430bc35e2d3210dd to your computer and use it in GitHub Desktop.
wheel.urdf.xacro
<?xml version="1.0"?>
<robot name="wheel" xmlns:xacro="http://ros.org/wiki/xacro" >
<xacro:property name="wheel_kp" value="600000" />
<xacro:property name="wheel_kd" value="3" />
<xacro:property name="wheel_mu1" value="10000000" />
<xacro:property name="wheel_mu2" value="10000000" />
<xacro:macro name="wheel" params="wheel_prefix parent_link *joint_pose">
<!-- Wheel Link -->
<link name="${wheel_prefix}_wheel_link">
<inertial>
<mass value="0.144" />
<origin xyz="0 0 0" />
<inertia ixx="0.00008929863" ixy="0" ixz="0" iyy="0.000168983" iyz="0" izz="0.00008929863" />
</inertial>
<visual>
<xacro:if value="$(arg mesh_enabled)">
<origin xyz="0 0 0" rpy="0 0 ${M_PI/2}" />
<geometry>
<mesh filename="package://onebot_description/meshes/wheel.dae" />
</geometry>
</xacro:if>
<xacro:unless value="$(arg mesh_enabled)">
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
<geometry>
<cylinder length="0.02" radius="0.04688" />
</geometry>
</xacro:unless>
</visual>
<collision>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
<geometry>
<cylinder length="0.02" radius="0.04688" />
</geometry>
</collision>
</link>
<!-- Wheel Joint -->
<joint name="${wheel_prefix}_wheel" type="continuous">
<parent link="${parent_link}"/>
<child link="${wheel_prefix}_wheel_link"/>
<xacro:insert_block name="joint_pose"/>
<axis xyz="0 1 0" rpy="0 0 0" />
<dynamics damping="0.5" friction="100.0" />
</joint>
<gazebo reference="${wheel_prefix}_wheel_link">
<mu1 value="${wheel_mu1}"/>
<mu2 value="${wheel_mu2}"/>
<kp>${wheel_kp}</kp>
<kd>${wheel_kd}</kd>
<dampingFactor>0.05</dampingFactor>
<fdir1 value="1 0 0"/>
</gazebo>
<transmission name="${wheel_prefix}_wheel_trans" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="${wheel_prefix}_wheel_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="${wheel_prefix}_wheel">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
</transmission>
</xacro:macro>
</robot>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment