jumeau_pioneer3DX/Projet/pioneer_description/urdf/pioneer3dx_wheel.xacro

112 lines
3.3 KiB
Text
Raw Normal View History

<?xml version="1.0"?>
<robot
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:xacro="http://ros.org/wiki/xacro"
>
<!--<xacro:include filename="$(find pioneer_description)/defs/materials.xacro"/>-->
<!-- Properties (Constants) -->
<xacro:property name="M_PI" value="3.14159"/>
<!-- Right/Left Hubcap + Wheel -->
<xacro:macro name="p3dx_wheel" params="suffix parent reflect">
<link name="p3dx_${suffix}_wheel">
<inertial>
<mass value="0.5"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.012411765597" ixy="0" ixz="0"
iyy="0.015218160428" iyz="0" izz="0.011763977943"/>
</inertial>
<visual name="base_visual">
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry name="pioneer_geom">
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/${suffix}_wheel.stl"/>
</geometry>
<material name="WheelBlack">
<color rgba="0.117 0.117 0.117 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="${-3.1415927/2} 0 0"/>
<geometry>
<!--<mesh filename="package://pioneer_description/meshes/p3dx_meshes/${suffix}_wheel.stl"/>-->
<cylinder radius="0.09" length="0.01"/>
</geometry>
</collision>
</link>
<joint name="base_${suffix}_hubcap_joint" type="fixed">
<!--<origin xyz="0 ${reflect*0.158} 0.091" rpy="0 0 0"/>-->
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="p3dx_${suffix}_wheel"/>
<child link="p3dx_${suffix}_hubcap"/>
</joint>
<link name="p3dx_${suffix}_hubcap">
<inertial>
<mass value="0.01"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.012411765597" ixy="0" ixz="0"
iyy="0.015218160428" iyz="0" izz="0.011763977943"/>
</inertial>
<visual name="base_visual">
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry name="pioneer_geom">
<mesh filename="package://pioneer_description/meshes/p3dx_meshes/${suffix}_hubcap.stl"/>
</geometry>
<material name="HubcapYellow">
<color rgba="1.0 0.811 0.151 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0 0 0"/>
</geometry>
</collision>
</link>
<transmission type="pr2_mechanism_model/SimpleTransmission" name="${parent}_${suffix}_wheel_trans">
<actuator name="base_${suffix}_wheel_motor" />
<joint name="base_${suffix}_wheel_joint" />
<mechanicalReduction>${reflect * 624/35 * 80/19}</mechanicalReduction>
</transmission>
<joint name="base_${suffix}_wheel_joint" type="continuous">
<axis xyz="0 1 0"/>
<anchor xyz="0 0 0"/>
<limit effort="100" velocity="100" />
<joint_properties damping="0.0" friction="0.0" />
<origin xyz="0 ${reflect*0.158} 0.091" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="p3dx_${suffix}_wheel"/>
</joint>
<gazebo reference="p3dx_${suffix}_hubcap">
<material value="Gazebo/Yellow"/>
</gazebo>
<gazebo reference="p3dx_${suffix}_wheel">
<material value="Gazebo/Black"/>
<elem key="mu1" value="0.5" />
<elem key="mu2" value="50.0" />
<elem key="kp" value="100000000.0" />
<elem key="kd" value="1.0" />
</gazebo>
</xacro:macro>
</robot>