cps_loki_description/urdf/diffbot_description.urdf.xacro.bak3
bjoernellens1 5cec9ab2fd
update
2023-11-20 10:06:40 +01:00

394 lines
17 KiB
XML

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="diffbot" params="prefix">
<!-- Constants for robot dimensions -->
<xacro:property name="PI" value="3.1415926535897931"/>
<xacro:property name="base_mass" value="0.3" /> <!-- arbitrary value for base mass -->
<xacro:property name="base_width" value="0.25" /> <!-- Updated wheel spacing to 25cm -->
<xacro:property name="base_length" value="0.34" />
<xacro:property name="base_height" value="0.1" />
<xacro:property name="wheel_mass" value="0.3" />
<!-- arbitrary value for wheel mass -->
<xacro:property name="wheel_len" value="0.020" />
<xacro:property name="wheel_radius" value="0.0625" />
<xacro:property name="caster_wheel_mass" value="0.1" /> <!-- arbitrary value for caster wheel mass -->
<xacro:property name="caster_wheel_radius" value="0.04" />
<xacro:property name="z_offset" value="-${base_height/2}" /> <!-- Space btw top of beam and the each joint -->
<!-- dummy link - used for ros2 control so it stops complaining? -->
<link name="${prefix}dummy">
</link>
<joint name="${prefix}dummy_joint" type="fixed">
<parent link="${prefix}dummy" />
<child link="${prefix}base_link" />
</joint>
<!-- Base Link -->
<link name="${prefix}base_link">
<visual>
<origin xyz="1.2116163827517698533e-16 -0.47900000000000020339 -0.044999999999999998335" rpy="-5.5511151231257814695e-17 -0 3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/right_motor.stl" />
</geometry>
<material name="right_motor_material">
<color rgba="0.49803921568627451677 0.49803921568627451677 0.49803921568627451677 1.0" />
</material>
</visual>
<collision>
<origin xyz="1.2116163827517698533e-16 -0.47900000000000020339 -0.044999999999999998335" rpy="-5.5511151231257814695e-17 -0 3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/right_motor.stl" />
</geometry>
</collision>
<visual>
<origin xyz="1.142227443712697323e-16 -0.47900000000000020339 -0.044999999999999998335" rpy="-5.5511151231257814695e-17 -0 3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/motor_bar_frame.stl" />
</geometry>
<material name="motor_bar_frame_material">
<color rgba="0.91764705882352937127 0.91764705882352937127 0.91764705882352937127 1.0" />
</material>
</visual>
<collision>
<origin xyz="1.142227443712697323e-16 -0.47900000000000020339 -0.044999999999999998335" rpy="-5.5511151231257814695e-17 -0 3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/motor_bar_frame.stl" />
</geometry>
</collision>
<visual>
<origin xyz="1.142227443712697323e-16 -0.47900000000000020339 -0.044999999999999998335" rpy="-5.5511151231257814695e-17 -0 3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/base_frame.stl" />
</geometry>
<material name="base_frame_material">
<color rgba="0.91764705882352937127 0.91764705882352937127 0.91764705882352937127 1.0" />
</material>
</visual>
<collision>
<origin xyz="1.142227443712697323e-16 -0.47900000000000020339 -0.044999999999999998335" rpy="-5.5511151231257814695e-17 -0 3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/base_frame.stl" />
</geometry>
</collision>
<visual>
<origin xyz="7.952827485173360274e-17 -0.4790000000000002589 -0.045000000000000012212" rpy="-5.5511151231257814695e-17 -0 3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/left_motor.stl" />
</geometry>
<material name="left_motor_material">
<color rgba="0.49803921568627451677 0.49803921568627451677 0.49803921568627451677 1.0" />
</material>
</visual>
<collision>
<origin xyz="7.952827485173360274e-17 -0.4790000000000002589 -0.045000000000000012212" rpy="-5.5511151231257814695e-17 -0 3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/left_motor.stl" />
</geometry>
</collision>
<visual>
<origin xyz="7.4868290514223760072e-17 -0.47900000000000020339 -0.044999999999999998335" rpy="-5.5511151231257814695e-17 -0 3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/caster_connector.stl" />
</geometry>
<material name="caster_connector_material">
<color rgba="0.91764705882352937127 0.91764705882352937127 0.91764705882352937127 1.0" />
</material>
</visual>
<collision>
<origin xyz="7.4868290514223760072e-17 -0.47900000000000020339 -0.044999999999999998335" rpy="-5.5511151231257814695e-17 -0 3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/caster_connector.stl" />
</geometry>
</collision>
<visual>
<origin xyz="1.1422274437126975695e-16 -0.47900000000000020339 -0.044999999999999998335" rpy="-5.5511151231257814695e-17 -0 3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/right_motor_frame.stl" />
</geometry>
<material name="right_motor_frame_material">
<color rgba="0.08627450980392156743 0.31764705882352939348 0.69019607843137253944 1.0" />
</material>
</visual>
<collision>
<origin xyz="1.1422274437126975695e-16 -0.47900000000000020339 -0.044999999999999998335" rpy="-5.5511151231257814695e-17 -0 3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/right_motor_frame.stl" />
</geometry>
</collision>
<visual>
<origin xyz="8.6467168755640818792e-17 -0.47900000000000020339 -0.04500000000000002609" rpy="-5.5511151231257814695e-17 -0 3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/left_motor_frame.stl" />
</geometry>
<material name="left_motor_frame_material">
<color rgba="0.08627450980392156743 0.31764705882352939348 0.69019607843137253944 1.0" />
</material>
</visual>
<collision>
<origin xyz="8.6467168755640818792e-17 -0.47900000000000020339 -0.04500000000000002609" rpy="-5.5511151231257814695e-17 -0 3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/left_motor_frame.stl" />
</geometry>
</collision>
<visual>
<origin xyz="1.1834508674736059205e-16 -0.4790000000000002589 -0.045000000000000012212" rpy="-5.5511151231257814695e-17 -0 3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/laser_frame.stl" />
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin xyz="1.1834508674736059205e-16 -0.4790000000000002589 -0.045000000000000012212" rpy="-5.5511151231257814695e-17 -0 3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/laser_frame.stl" />
</geometry>
</collision>
<visual>
<origin xyz="7.4868290514223760072e-17 -0.47900000000000020339 -0.044999999999999998335" rpy="-5.5511151231257814695e-17 -0 3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/caster_angle.stl" />
</geometry>
<material name="black"/>
</visual>
<collision>
<origin xyz="7.4868290514223760072e-17 -0.47900000000000020339 -0.044999999999999998335" rpy="-5.5511151231257814695e-17 -0 3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/caster_angle.stl" />
</geometry>
</collision>
<inertial>
<origin xyz="7.8715304751559223009e-17 -0.50594215569207112715 -0.048387297397152334577" rpy="0 0 0" />
<mass value="8.4777020573643113721" />
<inertia ixx="0.091076661684079157633" ixy="1.1626534456871032806e-17" ixz="2.9892835648942556204e-18" iyy="0.055622455227950687306" iyz="-0.010811144091914795182" izz="0.1312992311107717136" />
</inertial>
</link>
<joint name="${prefix}right_wheel_joint" type="continuous">
<parent link="${prefix}base_link"/>
<child link="${prefix}right_wheel"/>
<origin xyz="${base_length/2} 0 ${z_offset}" rpy="0 0 0"/> <!-- Updated wheel position -->
<axis xyz="0 -1 0"/>
<dynamics damping="0.2"/>
</joint>
<!-- right wheel Link -->
<link name="${prefix}right_wheel">
<visual>
<origin xyz="-0.10999999999999998668 0.060000000000000011657 0.125" rpy="-1.570796326794896558 -1.570796326794896558 0" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/left_wheel.stl" />
</geometry>
<material name="left_wheel_material">
<color rgba="0.50196078431372548323 0.50196078431372548323 0.50196078431372548323 1.0" />
</material>
</visual>
<collision>
<origin xyz="-0.10999999999999998668 0.060000000000000011657 0.125" rpy="-1.570796326794896558 -1.570796326794896558 0" />
<geometry>
<cylinder length="${wheel_len}" radius="${wheel_radius}"/>
</geometry>
</collision>
<inertial>
<origin xyz="1.3877787807814456755e-17 1.3877787807814456755e-17 -0.017500000000000015543" rpy="0 0 0" />
<mass value="0.43298678305638949038" />
<inertia ixx="0.00043196650576949035269" ixy="0" ixz="1.8666117243005040269e-36" iyy="0.00043196650576949029848" iyz="0" izz="0.00078373880522818965139" />
</inertial>
</link>
<!-- left wheel joint -->
<joint name="${prefix}left_wheel_joint" type="revolute">
<origin xyz="0.12500000000000013878 -0.58900000000000007905 -0.10500000000000003775" rpy="1.57079632679489678 -1.1102230246251567869e-16 -1.570796326794896558" />
<parent link="${prefix}base_link" />
<child link="${prefix}left_wheel" />
<axis xyz="0 0 1" />
<limit effort="1" velocity="20" />
<joint_properties friction="0.0" />
</joint>
<!-- left wheel Link -->
<link name="${prefix}left_wheel">
<visual>
<origin xyz="0 0 0" rpy="${PI/2} 0 0"/>
<geometry>
<cylinder length="${wheel_len}" radius="${wheel_radius}"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin xyz="-0.10999999999999998668 0.05999999999999999778 0.125" rpy="-1.570796326794896558 -1.570796326794896558 0" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/left_wheel.stl" />
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" rpy="${PI/2} 0 0"/>
<mass value="${wheel_mass}"/>
<inertia
ixx="${wheel_mass / 12.0 * (3*wheel_radius + wheel_len*wheel_len)}" ixy="0.0" ixz="0.0"
iyy="${wheel_mass / 12.0 * wheel_radius*wheel_radius}" iyz="0.0"
izz="${wheel_mass / 12.0 * wheel_radius*wheel_radius}"/>
</inertial>
</link>
<joint name="${prefix}caster_wheel_joint" type="fixed">
<parent link="${prefix}base_link"/>
<child link="${prefix}caster_wheel"/>
<origin xyz="${-base_length/2} 0 ${z_offset}" rpy="0 0 0"/> <!-- Updated caster wheel position -->
</joint>
<!-- caster wheel Link -->
<link name="${prefix}caster_wheel">
<visual>
<origin xyz="1.1302212892091925974e-17 5.5511151231257827021e-17 0" rpy="3.141592653589793116 -8.3802055560433424155e-17 -3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/caster_wheel.stl" />
</geometry>
<material name="caster_wheel_material">
<color rgba="0.50196078431372548323 0.50196078431372548323 0.50196078431372548323 1.0" />
</material>
</visual>
<collision>
<origin xyz="1.1302212892091925974e-17 5.5511151231257827021e-17 0" rpy="3.141592653589793116 -8.3802055560433424155e-17 -3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/caster_wheel.stl" />
</geometry>
</collision>
<visual>
<origin xyz="2.6961896103443574151e-18 0 0" rpy="3.141592653589793116 -0 0" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/caster_bearing_frame.stl" />
</geometry>
<material name="caster_bearing_frame_material">
<color rgba="0.80000000000000004441 0.80000000000000004441 0.80000000000000004441 1.0" />
</material>
</visual>
<collision>
<origin xyz="2.6961896103443574151e-18 0 0" rpy="3.141592653589793116 -0 0" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/caster_bearing_frame.stl" />
</geometry>
</collision>
<visual>
<origin xyz="-1.232595164407830946e-32 0 0" rpy="3.141592653589793116 4.7934256393637874986e-32 -3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/caster_frame_left.stl" />
</geometry>
<material name="caster_frame_left_material">
<color rgba="0.90196078431372550543 0.90196078431372550543 0.90196078431372550543 1.0" />
</material>
</visual>
<collision>
<origin xyz="-1.232595164407830946e-32 0 0" rpy="3.141592653589793116 4.7934256393637874986e-32 -3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/caster_frame_left.stl" />
</geometry>
</collision>
<visual>
<origin xyz="-1.232595164407830946e-32 0 0" rpy="3.141592653589793116 4.7934256393637874986e-32 -3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/caster_frame_top.stl" />
</geometry>
<material name="caster_frame_top_material">
<color rgba="0.80000000000000004441 0.80000000000000004441 0.80000000000000004441 1.0" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<sphere radius="${caster_wheel_radius}"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<sphere radius="${caster_wheel_radius}"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<origin xyz="-1.232595164407830946e-32 0 0" rpy="3.141592653589793116 4.7934256393637874986e-32 -3.141592653589793116" />
<geometry>
<mesh filename="file://$(find cps_loki_description)/mesh/caster_frame_right.stl" />
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="${caster_wheel_mass}"/>
<inertia
ixx="${2.0/5.0 * caster_wheel_mass * caster_wheel_radius * caster_wheel_radius}"
ixy="0.0" ixz="0.0"
iyy="${2.0/5.0 * caster_wheel_mass * caster_wheel_radius * caster_wheel_radius}"
iyz="0.0"
izz="${2.0/5.0 * caster_wheel_mass * caster_wheel_radius * caster_wheel_radius}"/>
</inertial>
</link>
<!-- laser_link -->
<link name="${prefix}laser_link">
<collision>
<origin xyz="${base_length/2} 0 ${base_height}" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.1"/>
</geometry>
</collision>
<visual>
<origin xyz="${base_length/2} 0 ${base_height}" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.1"/>
</geometry>
<material name="green"/>
</visual>
<inertial>
<origin xyz="${base_length/2} 0 ${base_height}" rpy="0 0 0"/>
<mass value="0.1"/>
<inertia
ixx="0.001" ixy="0.0" ixz="0.0"
iyy="0.001" iyz="0.0"
izz="0.001"/>
</inertial>
</link>
<!-- camera_link -->
<link name="${prefix}camera_link">
<collision>
<origin xyz="${base_length/2} 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.1"/>
</geometry>
</collision>
<visual>
<origin xyz="${base_length/2} 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.1"/>
</geometry>
<material name="blue"/>
</visual>
<inertial>
<origin xyz="${base_length/2} 0 0" rpy="0 0 0"/>
<mass value="0.1"/>
<inertia
ixx="0.001" ixy="0.0" ixz="0.0"
iyy="0.001" iyz="0.0"
izz="0.001"/>
</inertial>
</link>
<!-- Camera Joint -->
<joint name="${prefix}camera_joint" type="revolute">
<origin xyz="9.7569399001892381731e-17 -0.6290000000000002256 -0.045000000000000005274" rpy="6.1062266354383530837e-16 1.1102230246251567869e-16 3.141592653589793116" />
<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>