XTDrone/sitl_config/usv/wamv_description/urdf/wamv_base.urdf.xacro

132 lines
3.9 KiB
XML

<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="wam-v">
<!-- Macro for creating the main collisions as simple shapes. -->
<xacro:macro name="main_collisions" params="prefix reflect:=1">
<!-- Main float -->
<collision name="${prefix}_float">
<origin xyz="-0.4 ${1.03*reflect} 0.2" rpy="${0*reflect} 1.57 0" />
<geometry>
<cylinder length="4" radius="0.2" />
</geometry>
</collision>
<collision name="${prefix}_mid_float">
<origin xyz="1.85 ${1.03*reflect} 0.3" rpy="${0*reflect} 1.38 0" />
<geometry>
<cylinder length="0.5" radius="0.17" />
</geometry>
</collision>
<collision name="${prefix}_front_float">
<origin xyz="2.3 ${1.03*reflect} 0.4" rpy="${0*reflect} 1.3 0" />
<geometry>
<cylinder length="0.45" radius="0.12" />
</geometry>
</collision>
<!-- Front beam -->
<collision name="front_${prefix}_beam_lower">
<origin xyz="0.9 ${0.85*reflect} 1" rpy="${0.78*reflect} 0 0" />
<geometry>
<cylinder length="0.5" radius="0.04" />
</geometry>
</collision>
<collision name="front_${prefix}_beam_upper">
<origin xyz="0.9 ${0.6*reflect} 1.18" rpy="${1.35*reflect} 0 0" />
<geometry>
<cylinder length="0.2" radius="0.04" />
</geometry>
</collision>
<!-- Mid beam -->
<collision name="mid_${prefix}_beam_lower">
<origin xyz="-0.65 ${0.99*reflect} 0.7" rpy="${0.1*reflect} 0.25 0" />
<geometry>
<cylinder length="0.45" radius="0.03" />
</geometry>
</collision>
<collision name="mid_${prefix}_beam_medium">
<origin xyz="-0.57 ${0.87*reflect} 1.05" rpy="${0.75*reflect} 0.25 0" />
<geometry>
<cylinder length="0.32" radius="0.03" />
</geometry>
</collision>
<collision name="mid_${prefix}_beam_upper">
<origin xyz="-0.55 ${0.65*reflect} 1.17" rpy="${1.35*reflect} 0.25 0" />
<geometry>
<cylinder length="0.3" radius="0.03" />
</geometry>
</collision>
<!-- Rear beam -->
<collision name="rear_${prefix}_beam_lower">
<origin xyz="-0.74 ${1.03*reflect} 0.7" rpy="${0*reflect} -0.15 0" />
<geometry>
<cylinder length="0.45" radius="0.03" />
</geometry>
</collision>
<collision name="rear_${prefix}_beam_medium">
<origin xyz="-0.79 ${0.91*reflect} 1.05" rpy="${0.75*reflect} -0.15 0" />
<geometry>
<cylinder length="0.32" radius="0.03" />
</geometry>
</collision>
<collision name="rear_${prefix}_beam_upper">
<origin xyz="-0.81 ${0.67*reflect} 1.18" rpy="${1.45*reflect} -0.15 0" />
<geometry>
<cylinder length="0.3" radius="0.03" />
</geometry>
</collision>
<!-- Joint -->
<collision name="${prefix}_joint">
<origin xyz="0.58 ${1.03*reflect} 0.6" rpy="${0*reflect} -0.6 0" />
<geometry>
<box size="0.65 0.2 0.1" />
</geometry>
</collision>
</xacro:macro>
<link name="base_link">
</link>
<joint name="dummy_joint" type = "fixed">
<parent link="base_link"/>
<child link="dummy_link"/>
</joint>
<!-- Basic model of the 16' WAM-V USV -->
<link name="dummy_link">
<visual>
<geometry>
<mesh filename="package://wamv_description/models/WAM-V-Base/mesh/WAM-V-Base.dae"/>
</geometry>
</visual>
<!-- Left base collisions -->
<xacro:main_collisions prefix="left" reflect="1" />
<!-- Right side collisions -->
<xacro:main_collisions prefix="right" reflect="-1" />
<!-- Top base -->
<collision name="top_base">
<origin xyz="0 -0 1.25" rpy="0 0 0" />
<geometry>
<box size="1.85 1 0.1" />
</geometry>
</collision>
<inertial>
<!-- From WAM-V spec sheet -->
<mass value="180.0"/>
<inertia ixx="120.0" ixy="0.0" ixz="0.0" iyy="393" iyz="0.0" izz="446.0"/>
</inertial>
</link>
</robot>