"> "> ">
<?xml version="1.0" ?>
<robot name="iiwa_14_r820_robot" xmlns:xacro="<http://www.ros.org/wiki/xacro>">
    <xacro:include filename="$(find iiwa_14_r820_robot_description)/urdf/insert_transmission.urdf.xacro"/>

    <link name="world"/>
    <link name="base_link">
        <visual>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <mesh filename="package://iiwa_14_r820_robot_description/meshes/base.dae" scale="1 1 1"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <mesh filename="package://iiwa_14_r820_robot_description/meshes/base.dae" scale="1 1 1"/>
            </geometry>
        </collision>
        <inertial>
            <origin xyz="-0.012827 0.000000 0.071509" rpy="0 0 0"/>
            <mass value="7.040753"/>
            <inertia ixx="0.031178" ixy="0.0" ixz="0.000869" iyy="0.039643" iyz="0.0" izz="0.043039"/>
        </inertial>
    </link>

    <joint name="base_fixed_joint" type="fixed">
        <parent link="world"/>
        <child link="base_link"/>
        <origin xyz="0 0 0" rpy="0 0 0"/>
    </joint>

    <link name="link1">
        <visual>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <mesh filename="package://iiwa_14_r820_robot_description/meshes/link1.dae" scale="1 1 1"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <mesh filename="package://iiwa_14_r820_robot_description/meshes/link1.dae" scale="1 1 1"/>
            </geometry>
        </collision>
        <inertial>
            <origin xyz="0.000000 -0.033792 0.122396" rpy="0 0 0"/>
            <mass value="5.280822"/>
            <inertia ixx="0.042384" ixy="0.0" ixz="0.0" iyy="0.042760" iyz="0.006329" izz="0.015839"/>
        </inertial>
    </link>

    <joint name="a1" type="revolute">
        <parent link="base_link"/>
        <child link="link1"/>
        <origin xyz="0 0 0.1575" rpy="0 0 0"/>
        <axis xyz="0 0 1"/>
        <limit effort="1000" velocity="${85*pi/180}" lower="${-170*pi/180}" upper="${170*pi/180}"/>
    </joint>
    <xacro:insert_position_transmission name="a1"/>

    <link name="link2">
        <visual>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <mesh filename="package://iiwa_14_r820_robot_description/meshes/link2.dae" scale="1 1 1"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <mesh filename="package://iiwa_14_r820_robot_description/meshes/link2.dae" scale="1 1 1"/>
            </geometry>
        </collision>
        <inertial>
            <origin xyz="0.000151 0.041985 0.058817" rpy="0 0 0"/>
            <mass value="5.079142"/>
            <inertia ixx="0.039318" ixy="-0.000029" ixz="0.000043" iyy="0.039093" iyz="0.006282" izz="0.014157"/>
        </inertial>
    </link>

    <joint name="a2" type="revolute">
        <parent link="link1"/>
        <child link="link2"/>
        <origin xyz="0 0 0.2025" rpy="0 0 0"/>
        <axis xyz="0 1 0"/>
        <limit effort="1000" velocity="${85*pi/180}" lower="${-120*pi/180}" upper="${120*pi/180}"/>
    </joint>
    <xacro:insert_position_transmission name="a2"/>

    <link name="link3">
        <visual>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <mesh filename="package://iiwa_14_r820_robot_description/meshes/link3.dae" scale="1 1 1"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <mesh filename="package://iiwa_14_r820_robot_description/meshes/link3.dae" scale="1 1 1"/>
            </geometry>
        </collision>
        <inertial>
            <origin xyz="0.000000 0.029560 0.126713" rpy="0 0 0"/>
            <mass value="4.080785"/>
            <inertia ixx="0.032025" ixy="0.0" ixz="0.0" iyy="0.030392" iyz="-0.006236" izz="0.009775"/>
        </inertial>
    </link>

    <joint name="a3" type="revolute">
        <parent link="link2"/>
        <child link="link3"/>
        <origin xyz="0 0 0.2045" rpy="0 0 0"/>
        <axis xyz="0 0 1"/>
        <limit effort="1000" velocity="${100*pi/180}" lower="${-170*pi/180}" upper="${170*pi/180}"/>
    </joint>
    <xacro:insert_position_transmission name="a3"/>

    <link name="link4">
        <visual>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <mesh filename="package://iiwa_14_r820_robot_description/meshes/link4.dae" scale="1 1 1"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <mesh filename="package://iiwa_14_r820_robot_description/meshes/link4.dae" scale="1 1 1"/>
            </geometry>
        </collision>
        <inertial>
            <origin xyz="0.000000 -0.034763 0.067428" rpy="0 0 0"/>
            <mass value="3.520877"/>
            <inertia ixx="0.022107" ixy="0.0" ixz="0.0" iyy="0.021068" iyz="-0.003659" izz="0.007887"/>
        </inertial>
    </link>

    <joint name="a4" type="revolute">
        <parent link="link3"/>
        <child link="link4"/>
        <origin xyz="0 0 0.2155" rpy="0 0 0"/>
        <axis xyz="0 1 0"/>
        <limit effort="1000" velocity="${75*pi/180}" lower="${-120*pi/180}" upper="${120*pi/180}"/>
    </joint>
    <xacro:insert_position_transmission name="a4"/>

    <link name="link5">
        <visual>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <mesh filename="package://iiwa_14_r820_robot_description/meshes/link5.dae" scale="1 1 1"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <mesh filename="package://iiwa_14_r820_robot_description/meshes/link5.dae" scale="1 1 1"/>
            </geometry>
        </collision>
        <inertial>
            <origin xyz="-0.000120 -0.021386 0.075460" rpy="0 0 0"/>
            <mass value="2.176392"/>
            <inertia ixx="0.012947" ixy="0.000002" ixz="-0.000001" iyy="0.011178" iyz="0.003970" izz="0.005740"/>
        </inertial>
    </link>

    <joint name="a5" type="revolute">
        <parent link="link4"/>
        <child link="link5"/>
        <origin xyz="0 0 0.1845" rpy="0 0 0"/>
        <axis xyz="0 0 1"/>
        <limit effort="1000" velocity="${130*pi/180}" lower="${-170*pi/180}" upper="${170*pi/180}"/>
    </joint>
    <xacro:insert_position_transmission name="a5"/>

    <link name="link6">
        <visual>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <mesh filename="package://iiwa_14_r820_robot_description/meshes/link6.dae" scale="1 1 1"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <mesh filename="package://iiwa_14_r820_robot_description/meshes/link6.dae" scale="1 1 1"/>
            </geometry>
        </collision>
        <inertial>
            <origin xyz="0.000000 0.061033 0.000573" rpy="0 0 0"/>
            <mass value="2.324820"/>
            <inertia ixx="0.006291" ixy="0.0" ixz="0.0" iyy="0.006022" iyz="0.000314" izz="0.004584"/>
        </inertial>
    </link>

    <joint name="a6" type="revolute">
        <parent link="link5"/>
        <child link="link6"/>
        <origin xyz="0 -0.0607 0.2155" rpy="0 0 0"/>
        <axis xyz="0 1 0"/>
        <limit effort="1000" velocity="${135*pi/180}" lower="${-120*pi/180}" upper="${120*pi/180}"/>
    </joint>
    <xacro:insert_position_transmission name="a6"/>

    <link name="link7">
        <visual>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <mesh filename="package://iiwa_14_r820_robot_description/meshes/link7.dae" scale="1 1 1"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <mesh filename="package://iiwa_14_r820_robot_description/meshes/link7.dae" scale="1 1 1"/>
            </geometry>
        </collision>
        <inertial>
            <origin xyz="0.000002 0.000002 0.017301" rpy="0 0 0"/>
            <mass value="0.396408"/>
            <inertia ixx="0.000282" ixy="0.0" ixz="0.0" iyy="0.000278" iyz="0.0" izz="0.000431"/>
        </inertial>
    </link>

    <joint name="a7" type="revolute">
        <parent link="link6"/>
        <child link="link7"/>
        <origin xyz="0 0.0607 0.0809" rpy="0 0 0"/>
        <axis xyz="0 0 1"/>
        <limit effort="1000" velocity="${135*pi/180}" lower="${-175*pi/180}" upper="${175*pi/180}"/>
    </joint>
    <xacro:insert_position_transmission name="a7"/>
</robot>