143 lines
3.9 KiB
XML
Executable File
143 lines
3.9 KiB
XML
Executable File
<?xml version="1.0"?>
|
|
<robot name="robot" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
|
<!--
|
|
Robot model taken from http://wiki.ros.org/pr2_mechanism/Tutorials/SImple%20URDF-Controller%20Example
|
|
-->
|
|
<!-- Constants for robot dimensions -->
|
|
<xacro:property name="PI" value="3.1415926535897931"/>
|
|
<xacro:property name="width" value="0.5" /> <!-- Square dimensions (widthxwidth) of beams -->
|
|
<xacro:property name="wheel_radius" value="0.11" /> <!-- Link 1 -->
|
|
<xacro:property name="thickness" value="0.086" /> <!-- Link 2 -->
|
|
<xacro:property name="axel_offset" value="0.05" /> <!-- Space btw top of beam and the each joint -->
|
|
|
|
<!-- Links: inertial,visual,collision -->
|
|
<link name="base_link">
|
|
<inertial>
|
|
<!-- origin is relative -->
|
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
|
<mass value="5"/>
|
|
<inertia ixx="5" ixy="0" ixz="0" iyy="5" iyz="0" izz="5"/>
|
|
</inertial>
|
|
<visual>
|
|
<geometry>
|
|
<box size="${width} 0.1 0.1"/>
|
|
</geometry>
|
|
</visual>
|
|
<collision>
|
|
<!-- origin is relative -->
|
|
<origin xyz="0 0 0"/>
|
|
<geometry>
|
|
<box size="${width} 0.1 0.1"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
|
|
|
|
<link name="base_footprint">
|
|
<visual>
|
|
<geometry>
|
|
<sphere radius="0.01"/>
|
|
</geometry>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0 0"/>
|
|
<geometry>
|
|
<sphere radius="0.00000001"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="base_footprint_joint" type="fixed">
|
|
<origin xyz="0 0 ${wheel_radius}" rpy="0 0 0"/>
|
|
<child link="base_link"/>
|
|
<parent link="base_footprint"/>
|
|
</joint>
|
|
|
|
|
|
<link name="wheel1">
|
|
<inertial>
|
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
|
<mass value="1"/>
|
|
<inertia ixx="0.2" ixy="0" ixz="0" iyy="0.2" iyz="0" izz="0.2"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin xyz="0 0 0" rpy="0 ${PI/2} 0"/>
|
|
<geometry>
|
|
<sphere radius="${wheel_radius}"/>
|
|
</geometry>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0 0" rpy="0 ${PI/2} 0"/>
|
|
<geometry>
|
|
<sphere radius="${wheel_radius}"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="joint_w1" type="continuous">
|
|
<parent link="base_link"/>
|
|
<child link="wheel1"/>
|
|
<origin xyz="${width/2+axel_offset} 0 0" rpy="${-PI/2} 0 0"/>
|
|
<axis xyz="0 1 0"/>
|
|
</joint>
|
|
|
|
|
|
<link name="wheel2">
|
|
<inertial>
|
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
|
<mass value="1"/>
|
|
<inertia ixx="0.2" ixy="0" ixz="0" iyy="0.2" iyz="0" izz="0.2"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin xyz="0 0 0" rpy="0 ${PI/2} 0"/>
|
|
<geometry>
|
|
<sphere radius="${wheel_radius}"/>
|
|
</geometry>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0 0" rpy="0 ${PI/2} 0"/>
|
|
<geometry>
|
|
<sphere radius="${wheel_radius}"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="joint_w2" type="continuous">
|
|
<parent link="base_link"/>
|
|
<child link="wheel2"/>
|
|
<origin xyz="${-width/2-axel_offset} 0 0" rpy="${-PI/2} 0 0"/>
|
|
<axis xyz="0 1 0"/>
|
|
</joint>
|
|
|
|
|
|
<!-- Transmission is important to link the joints and the controller -->
|
|
<transmission name="joint_w1_trans" type="SimpleTransmission">
|
|
<actuator name="joint_w1_motor" />
|
|
<joint name="joint_w1" />
|
|
<mechanicalReduction>1</mechanicalReduction>
|
|
<motorTorqueConstant>1</motorTorqueConstant>
|
|
</transmission>
|
|
|
|
<transmission name="joint_w2_trans" type="SimpleTransmission">
|
|
<actuator name="joint_w2_motor" />
|
|
<joint name="joint_w2" />
|
|
<mechanicalReduction>1</mechanicalReduction>
|
|
<motorTorqueConstant>1</motorTorqueConstant>
|
|
</transmission>
|
|
|
|
<!-- Colour -->
|
|
<gazebo reference="base_link">
|
|
<material>Gazebo/Green</material>
|
|
</gazebo>
|
|
|
|
<gazebo reference="wheel1">
|
|
<material>Gazebo/Red</material>
|
|
</gazebo>
|
|
|
|
<gazebo reference="wheel2">
|
|
<material>Gazebo/Blue</material>
|
|
</gazebo>
|
|
|
|
<gazebo reference="base_footprint">
|
|
<material>Gazebo/Purple</material>
|
|
</gazebo>
|
|
|
|
</robot>
|