aquanaute.urdf 6.52 KB
<?xml version="1.0"?>
<robot name="aquanaute">

    <material name="blue">
        <color rgba="0 0 0.8 1"/>
    </material>
    <material name="red">
        <color rgba="0.8 0 0 1"/>
    </material>
    <material name="green">
        <color rgba="0 0.8 0 1"/>
    </material>
    <material name="cyan">
        <color rgba="0 0.6 0.6 1"/>
    </material>
    <material name="yellow">
        <color rgba="0.8 0.8 0 1"/>
    </material>
    <material name="purple">
        <color rgba="0.5 0 0.5 1"/>
    </material>
    <material name="white">
        <color rgba="1 1 1 1"/>
    </material>
    <material name="gray">
        <color rgba="0.35 0.35 0.35 1"/>
    </material>
    <material name="black">
        <color rgba="0 0 0 1"/>
    </material>

   	<!-- * * * Link Definitions * * * -->
    <link name="base_link">
        <visual>
            <origin rpy="0.0 0 0" xyz="0 0 0"/>
            <geometry>
                <sphere radius="0.001"/>
            </geometry>
            <material name="blue"/>
        </visual>
    </link>

    <link name="platform_link">
        <inertial>
            <origin xyz="-0.024 0 -0007" rpy="0 0 0"/>
            <mass value="16"/>
            <inertia ixx="4.206" ixy="0.0" ixz="-0.031" iyy="4.588" iyz="0.0" izz="8.785"/>
        </inertial>

        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <mesh filename="package://aquanaute_description/models/meshes/Platform.stl"/>
            </geometry>
        </collision>

        <visual>
            <origin rpy="0.0 0 0" xyz="0 0 0"/>
            <geometry>
                <mesh filename="package://aquanaute_description/models/meshes/Platform.stl"/>
            </geometry>
            <material name="yellow"/>
        </visual>
    </link>

    <link name="right_hull_link">
        <inertial>
            <origin xyz="-0.124 0 -0.168" rpy="0 0 0"/>
            <mass value="10.45"/>
            <inertia ixx="0.244" ixy="3.346" ixz="0.009" iyy="4.974" iyz="-8.274" izz="4.965"/>
        </inertial>

        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <mesh filename="package://aquanaute_description/models/meshes/Hull.stl"/>
            </geometry>
        </collision>

        <visual>
            <origin rpy="0.0 0 0" xyz="0 0 0"/>
            <geometry>
                <mesh filename="package://aquanaute_description/models/meshes/Hull.stl"/>
            </geometry>
            <material name="red"/>
        </visual>
    </link>

    <link name="left_hull_link">
        <inertial>
            <origin xyz="-0.124 0 -0.168" rpy="0 0 0"/>
            <mass value="10.45"/>
            <inertia ixx="0.244" ixy="3.346" ixz="0.009" iyy="4.974" iyz="-8.274" izz="4.965"/>
        </inertial>

        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <mesh filename="package://aquanaute_description/models/meshes/Hull.stl"/>
            </geometry>
        </collision>

        <visual>
            <origin rpy="0.0 0 0" xyz="0 0 0"/>
            <geometry>
                <mesh filename="package://aquanaute_description/models/meshes/Hull.stl"/>
            </geometry>
            <material name="red"/>
        </visual>
    </link>

    <link name="motor_link">
        <inertial>
            <origin xyz="-0.133 0 -0.391" rpy="0 0 0"/>
            <mass value="6.6"/>
            <inertia ixx="0.072" ixy="3.604" ixz="-0.011" iyy="0.111" iyz="5.484" izz="0.042"/>
        </inertial>

        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <mesh filename="package://aquanaute_description/models/meshes/Motor.stl"/>
            </geometry>
        </collision>

        <visual>
            <origin rpy="0.0 0 0" xyz="0 0 0"/>
            <geometry>
                <mesh filename="package://aquanaute_description/models/meshes/Motor.stl"/>
            </geometry>
            <material name="purple"/>
        </visual>
    </link>

    <link name="sensor_frame_link">
        <inertial>
            <origin xyz="-0.007 0 0.379" rpy="0 0 0"/>
            <mass value="1.8"/>
            <inertia ixx="0.308" ixy="0.00" ixz="0.007" iyy="0.297"	iyz="0.00" izz="0.022"/>
        </inertial>
        
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <mesh filename="package://aquanaute_description/models/meshes/sensor_frame.stl"/>
            </geometry>
        </collision>

        <visual>
            <origin rpy="0.0 0 0" xyz="0 0 0"/>
            <geometry>
                <mesh filename="package://aquanaute_description/models/meshes/sensor_frame.stl"/>
            </geometry>
            <material name="cyan"/>
        </visual>
    </link>

    <!-- * * * Joint Definitions * * * -->
    <joint name="platform_base_joint" type="fixed">
    	<parent link="base_link"/>
    	<child link="platform_link"/>
    	<origin xyz="0 0 0" rpy="0 0 0"/>
	</joint>

    <joint name="right_hull_platform_joint" type="fixed">
    	<parent link="platform_link"/>
    	<child link="right_hull_link"/>
    	<origin xyz="-0.05 -0.7 -0.036" rpy="0 0 0"/>
	</joint>

    <joint name="left_hull_platform_joint" type="fixed">
    	<parent link="platform_link"/>
    	<child link="left_hull_link"/>
    	<origin xyz="-0.05 0.7 -0.036" rpy="0 0 0"/>
	</joint>

    <joint name="motor_platform_joint" type="fixed">
    	<parent link="base_link"/>
    	<child link="motor_link"/>
    	<origin xyz="-0.91 0.0 -0.09" rpy="0 0 0"/>
	</joint>

    <joint name="sensor_frame_platform_joint" type="fixed">
    	<parent link="base_link"/>
    	<child link="sensor_frame_link"/>
    	<origin xyz="-0.55 0.0 0.0" rpy="0 0 0"/>
	</joint>

    <!--
    <joint name="pitch_joint" type="revolute">
    	<parent link="roll_M1_link"/>
    	<child link="pitch_M2_link"/>
    	<origin xyz="0 0 0" rpy="0 -1.5708 0"/>
        <limit lower="0" upper="0.44" effort="0.1" velocity="0.005"/>
        <axis xyz="0 1 0"/>
	</joint>

    <joint name="yaw_joint" type="continuous">
    	<parent link="pitch_M2_link"/>
    	<child link="yaw_M3_link"/>
        <origin xyz="0.01 0 0" rpy="0 1.5708 0"/>
        <limit effort="0.1" velocity="0.01"/>
        <axis xyz="0 0 1"/>
	</joint>
    -->
    
    <!-- This is for color and physical properties in Gazebo, color won't work with the material tag in gazebo
    only for URDF coloring 
    <gazebo reference="roll_M1_link">
        <kp>1000.0</kp>
        <kd>10.0</kd>
        <mu1>10.0</mu1>
        <mu2>10.0</mu2>
        <material>Gazebo/Red</material>
    </gazebo>
    -->

</robot>