bot_mini_description/urdf/diffbot_description.urdf.xacro
bjoernellens1 966b49d3d8
update
2023-11-20 17:46:35 +01:00

225 lines
7.9 KiB
XML

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="diffbot" params="prefix">
<xacro:include filename="inertial_macros.xacro"/>
<!-- Constants for robot dimensions -->
<xacro:property name="PI" value="3.1415926535897931"/>
<!-- new properties -->
<xacro:property name="chassis_length" value="0.34"/>
<xacro:property name="chassis_width" value="0.26"/>
<xacro:property name="chassis_height" value="0.123"/>
<xacro:property name="chassis_mass" value="3.0"/>
<xacro:property name="wheel_radius" value="0.0625"/>
<xacro:property name="wheel_thickness" value="0.020"/>
<xacro:property name="wheel_mass" value="0.02"/>
<xacro:property name="wheel_offset_x" value="0.285748"/>
<xacro:property name="wheel_offset_y" value="0.33675"/>
<xacro:property name="wheel_offset_z" value="-0.035"/>
<xacro:property name="caster_wheel_radius" value="0.04"/>
<xacro:property name="caster_wheel_mass" value="0.01"/>
<xacro:property name="caster_wheel_offset_x" value="0.075"/>
<xacro:property name="caster_wheel_offset_z" value="${wheel_offset_z - wheel_radius + caster_wheel_radius}"/>
<xacro:property name="chassis_offset" value="0.065"/>
<!-- Base Link -->
<link name="${prefix}base_link">
</link>
<!-- Adding base_footprint for mapping (Needed by slam toolbox) -->
<joint name="${prefix}base_footprint_joint" type="fixed">
<parent link="${prefix}base_link" />
<child link="${prefix}base_footprint" />
<origin xyz="0 0 0" rpy="0 0 0" />
</joint>
<link name="${prefix}base_footprint">
</link>
<!-- CHASSIS LINK -->
<joint name="${prefix}chassis_joint" type="fixed">
<parent link="${prefix}base_link"/>
<child link="${prefix}chassis"/>
<origin xyz="${-chassis_length/2 + chassis_offset} 0 ${wheel_radius - wheel_offset_z}"/>
</joint>
<link name="${prefix}chassis">
<visual>
<origin xyz="0 0 0"/>
<geometry>
<box size="${chassis_length} ${chassis_width} ${chassis_height}"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin xyz="0 0 0"/>
<geometry>
<box size="${chassis_length} ${chassis_width} ${chassis_height}"/>
</geometry>
</collision>
<xacro:inertial_box mass="0.5" x="${chassis_length}" y="${chassis_width}" z="${chassis_height}">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_box>
</link>
<gazebo reference="chassis">
<material>Gazebo/Orange</material>
</gazebo>
<!-- RIGHT WHEEL -->
<joint name="${prefix}right_wheel_joint" type="continuous">
<parent link="${prefix}chassis"/>
<child link="${prefix}right_wheel"/>
<origin xyz="${chassis_length/2 - 0.075} -${wheel_offset_y/2 + wheel_thickness/2 + 0.01} ${wheel_offset_z}" rpy="${pi/2} 0 0" />
<axis xyz="0 0 -1"/>
<limit effort="1" velocity="20" />
<joint_properties friction="0.0"/>
</joint>
<link name="${prefix}right_wheel">
<visual>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_thickness}"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<geometry>
<sphere radius="${wheel_radius}"/>
</geometry>
</collision>
<xacro:inertial_cylinder mass="${wheel_mass}" length="${wheel_thickness}" radius="${wheel_radius}">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_cylinder>
</link>
<gazebo reference="right_wheel">
<material>Gazebo/Blue</material>
</gazebo>
<!-- LEFT WHEEL -->
<joint name="${prefix}left_wheel_joint" type="continuous">
<parent link="${prefix}chassis"/>
<child link="${prefix}left_wheel"/>
<origin xyz="${chassis_length/2 - 0.075} ${wheel_offset_y/2 + wheel_thickness/2 + 0.01} ${wheel_offset_z}" rpy="-${pi/2} 0 0" />
<axis xyz="0 0 1"/>
</joint>
<link name="${prefix}left_wheel">
<visual>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_thickness}"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<geometry>
<sphere radius="${wheel_radius}"/>
</geometry>
</collision>
<xacro:inertial_cylinder mass="${wheel_mass}" length="${wheel_thickness}" radius="${wheel_radius}">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_cylinder>
</link>
<gazebo reference="left_wheel">
<material>Gazebo/Blue</material>
</gazebo>
<!-- CASTER WHEEL -->
<joint name="${prefix}caster_wheel_joint" type="fixed">
<parent link="${prefix}chassis"/>
<child link="${prefix}caster_wheel"/>
<origin xyz="-${caster_wheel_offset_x*2} 0 ${caster_wheel_offset_z}"/>
</joint>
<link name="${prefix}caster_wheel">
<visual>
<geometry>
<sphere radius="${caster_wheel_radius}"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<geometry>
<sphere radius="${caster_wheel_radius}"/>
</geometry>
</collision>
<xacro:inertial_sphere mass="${caster_wheel_mass}" radius="${caster_wheel_radius}">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_sphere>
</link>
<gazebo reference="caster_wheel">
<material>Gazebo/White</material>
<mu1 value="0.001"/>
<mu2 value="0.001"/>
</gazebo>
<!-- LASER -->
<joint name="${prefix}laser_joint" type="fixed">
<parent link="${prefix}chassis"/>
<child link="${prefix}laser_frame"/>
<origin xyz="-0.07 0 10" rpy="0 0 ${pi}"/>
</joint>
<link name="${prefix}laser_frame">
<visual>
<geometry>
<cylinder radius="0.04" length="0.05"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<geometry>
<sphere radius="${caster_wheel_radius}"/>
</geometry>
</collision>
<xacro:inertial_sphere mass="${caster_wheel_mass}" radius="${caster_wheel_radius}">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_sphere>
</link>
<gazebo reference="laser_frame">
<material>Gazebo/White</material>
</gazebo>
<!-- camera_link -->
<link name="${prefix}camera_link">
<visual>
<origin xyz="0 0 0" rpy="0 -0 0" />
<geometry>
<mesh filename="package://cps_loki_description/mesh/camera_link_visual.stl"/>
</geometry>
<material name="camera_link_material">
<color rgba="0.26274509803921569651 0.28235294117647058432 0.30196078431372547213 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 -0 0" />
<geometry>
<mesh filename="package://cps_loki_description/mesh/camera_link_collision.stl"/>
</geometry>
</collision>
<inertial>
<origin xyz="5.3378961738576549005e-07 0.0016484827975361887251 -0.020840554768345870285" rpy="0 0 0"/>
<mass value="0.064008494238512375629" />
<inertia ixx="1.7394518695567356026e-05" ixy="-4.87317899857206066e-10" ixz="-1.7982620680900958214e-11" iyy="3.2074360900148983727e-05" iyz="2.0892555595878115295e-06" izz="2.8321439372619354409e-05" />
</inertial>
</link>
<!-- Camera Joint -->
<joint name="${prefix}camera_joint" type="fixed">
<origin xyz="${chassis_length / 2 - chassis_offset} 0 0" rpy="0 0 ${PI}" />
<parent link="${prefix}base_link" />
<child link="${prefix}camera_link" />
<axis xyz="0 0 1"/>
<limit effort="1" velocity="20" />
<joint_properties friction="0.0"/>
</joint>
</xacro:macro>
</robot>