This commit is contained in:
bjoernellens1 2023-11-20 12:29:13 +01:00 committed by GitHub
parent 576d85cf4a
commit fbd28c02cb
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23

View File

@ -2,196 +2,227 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"> <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="diffbot" params="prefix"> <xacro:macro name="diffbot" params="prefix">
<xacro:include filename="inertial_macros.xacro"/>
<!-- Constants for robot dimensions --> <!-- Constants for robot dimensions -->
<xacro:property name="PI" value="3.1415926535897931"/> <xacro:property name="PI" value="3.1415926535897931"/>
<xacro:property name="base_mass" value="0.3" />
<!-- arbitrary value for base mass --> <!-- new properties -->
<xacro:property name="base_width" value="0.26" /> <xacro:property name="chassis_length" value="0.34"/>
<!-- Updated wheel spacing to 25cm --> <xacro:property name="chassis_width" value="0.26"/>
<xacro:property name="base_length" value="0.34" /> <xacro:property name="chassis_height" value="0.123"/>
<xacro:property name="base_height" value="0.123" /> <xacro:property name="chassis_mass" value="3.0"/>
<xacro:property name="wheel_mass" value="0.3" /> <xacro:property name="wheel_radius" value="0.0625"/>
<!-- arbitrary value for wheel mass --> <xacro:property name="wheel_thickness" value="0.020"/>
<xacro:property name="wheel_len" value="0.020" /> <xacro:property name="wheel_mass" value="0.02"/>
<xacro:property name="wheel_radius" value="0.0625" /> <xacro:property name="wheel_offset_x" value="0.285748"/>
<xacro:property name="caster_wheel_mass" value="0.1" /> <xacro:property name="wheel_offset_y" value="0.33675"/>
<!-- arbitrary value for caster wheel mass --> <xacro:property name="wheel_offset_z" value="-0.035"/>
<xacro:property name="caster_wheel_radius" value="0.04" /> <xacro:property name="caster_wheel_radius" value="0.04"/>
<xacro:property name="z_offset" value="-${base_height/2}" /> <xacro:property name="caster_wheel_mass" value="0.01"/>
<!-- Offset of main Axis to center of base body (Axis of rotation for steering) --> <xacro:property name="caster_wheel_offset_x" value="0.075"/>
<xacro:property name="base_offset" value="0.11" /> <xacro:property name="caster_wheel_offset_z" value="${wheel_offset_z - wheel_radius + caster_wheel_radius}"/>
<!-- Materials -->
<material name="white">
<color rgba="1 1 1 1" />
</material>
<material name="orange">
<color rgba="1 0.3 0.1 1"/>
</material>
<material name="blue">
<color rgba="0.2 0.2 1 1"/>
</material>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
<material name="red">
<color rgba="1 0 0 1"/>
</material>
<material name="green">
<color rgba="0.0 0.8 0.0 1.0"/>
</material>
<material name="grey">
<color rgba="0.6 0.6 0.6 1.0"/>
</material>
<material name="grey2">
<color rgba="0.9 0.9 0.9 1.0"/>
</material>
<material name="lightGrey">
<color rgba="0.6 0.6 0.6 1.0"/>
</material>
<!-- Base Link --> <!-- Base Link -->
<link name="${prefix}base_link"> <link name="${prefix}base_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://cps_loki_description/mesh/base_link_visual.stl"/>
</geometry>
<material name="base_link_material">
<color rgba="0.80032179626883115375 0.81301836741632160788 0.83346199892499306383 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 -0 0" />
<geometry>
<mesh filename="package://cps_loki_description/mesh/base_link_collision.stl"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="8.4123950268139715547" />
<inertia ixx="0.090166990291185383777" ixy="4.7429179749238352248e-18" ixz="1.4209310488728267579e-18" iyy="0.055481261106946747064" iyz="-0.01112159061226025876" izz="0.13051099377067149065" />
</inertial>
</link> </link>
<!-- Adding base_footprint for mapping (Needed by slam toolbox) --> <!-- Adding base_footprint for mapping (Needed by slam toolbox) -->
<link name="${prefix}base_footprint">
</link>
<joint name="${prefix}base_footprint_joint" type="fixed"> <joint name="${prefix}base_footprint_joint" type="fixed">
<parent link="${prefix}base_link" /> <parent link="${prefix}base_link" />
<child link="${prefix}base_footprint" /> <child link="${prefix}base_footprint" />
<origin xyz="0 0 ${z_offset}" rpy="0 0 0" /> <origin xyz="0 0 0" rpy="0 0 0" />
</joint> </joint>
<!-- right wheel 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 + 0.065} 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"> <joint name="${prefix}right_wheel_joint" type="continuous">
<origin xyz="0 ${-0.125 - wheel_len /2} ${z_offset}" rpy="${PI / 2} 0 0" /> <parent link="${prefix}chassis"/>
<parent link="${prefix}base_link" /> <child link="${prefix}right_wheel"/>
<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"/> <axis xyz="0 0 -1"/>
<limit effort="1" velocity="20" /> <limit effort="1" velocity="20" />
<joint_properties friction="0.0"/> <joint_properties friction="0.0"/>
</joint> </joint>
<!-- right wheel Link -->
<link name="${prefix}right_wheel"> <link name="${prefix}right_wheel">
<visual> <visual>
<origin xyz="0 0 ${wheel_len}" rpy="0 -0 0" />
<geometry> <geometry>
<mesh filename="package://cps_loki_description/mesh/wheel_link_visual.stl"/> <cylinder radius="${wheel_radius}" length="${wheel_thickness}"/>
</geometry> </geometry>
<material name="wheel_link_material"> <material name="blue"/>
<color rgba="0.50196078431372548323 0.50196078431372548323 0.50196078431372548323 1.0"/>
</material>
</visual> </visual>
<collision> <collision>
<origin xyz="0 0 ${wheel_len}" rpy="0 -0 0" />
<geometry> <geometry>
<mesh filename="package://cps_loki_description/mesh/wheel_link_collision.stl"/> <sphere radius="${wheel_radius}"/>
</geometry> </geometry>
</collision> </collision>
<inertial> <xacro:inertial_cylinder mass="${wheel_mass}" length="${wheel_thickness}" radius="${wheel_radius}">
<origin xyz="-1.3877787807814456755e-17 -6.9388939039072283776e-18 -0.017500000000000029421" rpy="0 0 0"/> <origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="0.43298678305638949038" /> </xacro:inertial_cylinder>
<inertia ixx="0.00043196650576949035269" ixy="0" ixz="1.8666117243005040269e-36" iyy="0.00043196650576949029848" iyz="0" izz="0.00078373880522818965139" />
</inertial>
</link> </link>
<!-- left wheel joint --> <gazebo reference="right_wheel">
<material>Gazebo/Blue</material>
</gazebo>
<!-- LEFT WHEEL -->
<joint name="${prefix}left_wheel_joint" type="continuous"> <joint name="${prefix}left_wheel_joint" type="continuous">
<origin xyz="0 ${0.125 + wheel_len /2} ${z_offset}" rpy="${PI / 2} 0 0" /> <parent link="${prefix}chassis"/>
<parent link="${prefix}base_link" /> <child link="${prefix}left_wheel"/>
<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" /> <axis xyz="0 0 1"/>
<limit effort="1" velocity="20" />
<joint_properties friction="0.0" />
</joint> </joint>
<!-- left wheel Link -->
<link name="${prefix}left_wheel"> <link name="${prefix}left_wheel">
<visual> <visual>
<origin xyz="0 0 ${wheel_len}" rpy="0 -0 0" />
<geometry> <geometry>
<mesh filename="package://cps_loki_description/mesh/wheel_link_2_visual.stl"/> <cylinder radius="${wheel_radius}" length="${wheel_thickness}"/>
</geometry> </geometry>
<material name="wheel_link_2_material"> <material name="blue"/>
<color rgba="0.50196078431372548323 0.50196078431372548323 0.50196078431372548323 1.0"/>
</material>
</visual> </visual>
<collision> <collision>
<origin xyz="0 0 ${wheel_len}" rpy="0 -0 0" />
<geometry> <geometry>
<mesh filename="package://cps_loki_description/mesh/wheel_link_2_collision.stl"/> <sphere radius="${wheel_radius}"/>
</geometry> </geometry>
</collision> </collision>
<inertial> <xacro:inertial_cylinder mass="${wheel_mass}" length="${wheel_thickness}" radius="${wheel_radius}">
<origin xyz="-2.7755575615628913511e-17 0 -0.017500000000000015543" rpy="0 0 0"/> <origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="0.43298678305638949038" /> </xacro:inertial_cylinder>
<inertia ixx="0.00043196650576949035269" ixy="1.4778173856800390343e-52" ixz="-4.8081924471597460774e-36" iyy="0.00043196650576949029848" iyz="0" izz="0.00078373880522818965139" />
</inertial>
</link> </link>
<!-- caster wheel joint --> <gazebo reference="left_wheel">
<material>Gazebo/Blue</material>
</gazebo>
<!-- CASTER WHEEL -->
<joint name="${prefix}caster_wheel_joint" type="fixed"> <joint name="${prefix}caster_wheel_joint" type="fixed">
<origin xyz="-${base_length / 2 + base_offset} 0 -0.02" rpy="0 0 ${PI}" /> <parent link="${prefix}chassis"/>
<parent link="${prefix}base_link" /> <child link="${prefix}caster_wheel"/>
<child link="${prefix}caster_wheel" /> <origin xyz="-${caster_wheel_offset_x*2} 0 ${caster_wheel_offset_z}"/>
<axis xyz="0 0 1"/>
<limit effort="1" velocity="20" />
<joint_properties friction="0.0"/>
</joint> </joint>
<!-- caster wheel Link -->
<link name="${prefix}caster_wheel"> <link name="${prefix}caster_wheel">
<visual> <visual>
<origin xyz="0 0 0" rpy="0 -0 0" />
<geometry> <geometry>
<mesh filename="package://cps_loki_description/mesh/caster_link_visual.stl"/> <sphere radius="${caster_wheel_radius}"/>
</geometry> </geometry>
<material name="caster_link_material"> <material name="white"/>
<color rgba="0.69513764518117548974 0.69513764518117548974 0.69513764518117548974 1.0"/>
</material>
</visual> </visual>
<collision> <collision>
<origin xyz="0 0 0" rpy="0 -0 0" />
<geometry> <geometry>
<mesh filename="package://cps_loki_description/mesh/caster_link_collision.stl"/> <sphere radius="${caster_wheel_radius}"/>
</geometry> </geometry>
</collision> </collision>
<inertial> <xacro:inertial_sphere mass="${caster_wheel_mass}" radius="${caster_wheel_radius}">
<origin xyz="-0.0043392325658342043027 -0.026018163063004008662 -0.040087257391101506487" rpy="0 0 0"/> <origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="0.4365196214157913146" /> </xacro:inertial_sphere>
<inertia ixx="0.00065232223366267665706" ixy="-2.2812456870885095374e-05" ixz="-2.819328031928647945e-05" iyy="0.00051934268155350092177" iyz="-0.00016904771834628737077" izz="0.00028021186492738437085" />
</inertial>
</link> </link>
<!-- laser_link --> <gazebo reference="caster_wheel">
<link name="${prefix}laser_link"> <material>Gazebo/White</material>
<visual> <mu1 value="0.001"/>
<origin xyz="0 0 0" rpy="${PI} -0 0" /> <mu2 value="0.001"/>
<geometry> </gazebo>
<mesh filename="package://cps_loki_description/mesh/laser_link_visual.stl"/>
</geometry>
<material name="laser_link_material">
<color rgba="0.49803921568627451677 0.49803921568627451677 0.49803921568627451677 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="${PI} -0 0" />
<geometry>
<mesh filename="package://cps_loki_description/mesh/laser_link_collision.stl"/>
</geometry>
</collision>
<inertial>
<origin xyz="8.0502568807622093404e-21 2.7755575615628913511e-17 -0.01526549883836261258" rpy="${PI} 0 0"/>
<mass value="0.065307030550339775776" />
<inertia ixx="1.578111853789072904e-05" ixy="-4.8590457654361857326e-53" ixz="1.0816309858643350309e-52" iyy="1.5781118537890654501e-05" iyz="9.8088682514084147142e-38" izz="1.9760068210357054465e-05" />
</inertial>
</link>
<!-- laser_joint --> <!-- LASER -->
<joint name="${prefix}laser_joint" type="fixed"> <joint name="${prefix}laser_joint" type="fixed">
<origin xyz="-0.015 0 0.09" rpy="0 0 0"/> <parent link="${prefix}chassis"/>
<parent link="${prefix}base_link" /> <child link="${prefix}laser_frame"/>
<child link="${prefix}laser_link" /> <origin xyz="${chassis_length/2 - 0.15285} 0 ${chassis_height/2 + 0.030}" rpy="0 0 ${pi}"/>
<axis xyz="0 0 1"/>
<limit effort="1" velocity="20" />
<joint_properties friction="0.0"/>
</joint> </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 --> <!-- camera_link -->
<link name="${prefix}camera_link"> <link name="${prefix}camera_link">
<visual> <visual>