XTDrone/sitl_config/usv/wamv_description/urdf/thrusters/engine.xacro

66 lines
2.3 KiB
XML

<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="wam-v-two-engines">
<!-- Macro for inserting an engine with its propeller. -->
<xacro:macro name="engine" params="prefix position:='0 0 0' orientation:='0 0 0'">
<link name="${prefix}_engine_link">
<visual>
<geometry>
<mesh filename="package://wamv_description/models/engine/mesh/engine.dae"/>
</geometry>
</visual>
<collision name="${prefix}_engine_vertical_axis_collision">
<origin xyz="-0.16 0 -0.24" rpy="0 0 0" />
<geometry>
<box size="0.2 0.15 0.83" />
</geometry>
</collision>
<collision name="${prefix}_engine_rear_end_collision">
<origin xyz="-0.34 0 0.12" rpy="0 0 0" />
<geometry>
<box size="0.12 0.15 0.12" />
</geometry>
</collision>
<inertial>
<mass value="15"/>
<inertia ixx="0.889245" ixy="0.0" ixz="0.0" iyy="0.911125" iyz="0.0" izz="0.078125"/>
</inertial>
</link>
<link name="${prefix}_propeller_link">
<visual>
<geometry>
<mesh filename="package://wamv_description/models/propeller/mesh/propeller.dae"/>
</geometry>
</visual>
<collision name="${prefix}_propeller_collision">
<origin xyz="-0.08 0 0" rpy="0 1.57 0" />
<geometry>
<cylinder length="0.18" radius="0.24" />
</geometry>
</collision>
<inertial>
<mass value="0.5"/>
<inertia ixx="0.008545" ixy="0.0" ixz="0.0" iyy="0.008545" iyz="0.0" izz="0.0144"/>
</inertial>
</link>
<joint name="${prefix}_chasis_engine_joint" type="revolute">
<axis xyz="0 0 1"/>
<limit lower="${-pi}" upper="${pi}" effort="10" velocity="10"/>
<origin xyz="${position}" rpy="${orientation}"/>
<parent link="base_link"/>
<child link="${prefix}_engine_link"/>
</joint>
<joint name="${prefix}_engine_propeller_joint" type="continuous">
<axis rpy="0 0 0" xyz="1 0 0"/>
<parent link="${prefix}_engine_link"/>
<child link="${prefix}_propeller_link"/>
<origin rpy="0 0 0" xyz="-0.278156 0 -0.509371"/>
<limit effort="100" velocity="100" />
<dynamics friction="0.05" damping="0.05" />
</joint>
</xacro:macro>
</robot>