<?xml version="1.0" encoding="utf-8"?>
<!-- =================================================================================== -->
<!-- |    This document was autogenerated by xacro from panda_arm_hand.urdf.xacro      | -->
<!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | -->
<!-- =================================================================================== -->
<robot name="panda" xmlns:xacro="http://www.ros.org/wiki/xacro">
  <!-- add a new base link is just a slab with no collision -->
  <link name="track_x">
    <visual>
      <geometry>
        <box size="1 0.1 0.1"/>
      </geometry>
    </visual>
  </link>
  <link name="track_y">
    <visual>
      <geometry>
        <box size="0.1 1 0.1"/>
      </geometry>
    </visual>
  </link>
  <joint name="move_x" type="prismatic">
    <origin rpy="0 0 0" xyz="0 0 0.01"/>
    <parent link="track_x"/>
    <child link="track_y"/>
    <axis xyz="1 0 0"/>
    <limit effort="20" lower="-1" upper="1" velocity="0.2"/>
  </joint>
  <link name="panda_link0">
    <visual>
      <geometry>
        <mesh filename="franka_description/meshes/visual/link0.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="franka_description/meshes/collision/link0.stl"/>
      </geometry>
    </collision>
  </link>
  <joint name="move_y" type="prismatic">
    <origin rpy="0 0 0" xyz="0 0 0.01"/>
    <parent link="track_y"/>
    <child link="panda_link0"/>
    <axis xyz="0 1 0"/>
    <limit effort="20" lower="-1" upper="1" velocity="0.2"/>
  </joint>
  <link name="panda_link1">
    <visual>
      <geometry>
        <mesh filename="franka_description/meshes/visual/link1.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="franka_description/meshes/collision/link1.stl"/>
      </geometry>
    </collision>
  </link>
  <joint name="panda_joint1" type="revolute">
    <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
    <origin rpy="0 0 0" xyz="0 0 0.333"/>
    <parent link="panda_link0"/>
    <child link="panda_link1"/>
    <axis xyz="0 0 1"/>
    <limit effort="87" lower="-2.8973" upper="2.8973" velocity="2.1750"/>
  </joint>
  <link name="panda_link2">
    <visual>
      <geometry>
        <mesh filename="franka_description/meshes/visual/link2.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="franka_description/meshes/collision/link2.stl"/>
      </geometry>
    </collision>
  </link>
  <joint name="panda_joint2" type="revolute">
    <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-1.7628" soft_upper_limit="1.7628"/>
    <origin rpy="-1.57079632679 0 0" xyz="0 0 0"/>
    <parent link="panda_link1"/>
    <child link="panda_link2"/>
    <axis xyz="0 0 1"/>
    <limit effort="87" lower="-1.7628" upper="1.7628" velocity="2.1750"/>
  </joint>
  <link name="panda_link3">
    <visual>
      <geometry>
        <mesh filename="franka_description/meshes/visual/link3.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="franka_description/meshes/collision/link3.stl"/>
      </geometry>
    </collision>
  </link>
  <joint name="panda_joint3" type="revolute">
    <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
    <origin rpy="1.57079632679 0 0" xyz="0 -0.316 0"/>
    <parent link="panda_link2"/>
    <child link="panda_link3"/>
    <axis xyz="0 0 1"/>
    <limit effort="87" lower="-2.8973" upper="2.8973" velocity="2.1750"/>
  </joint>
  <link name="panda_link4">
    <visual>
      <geometry>
        <mesh filename="franka_description/meshes/visual/link4.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="franka_description/meshes/collision/link4.stl"/>
      </geometry>
    </collision>
  </link>
  <joint name="panda_joint4" type="revolute">
    <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-3.0718" soft_upper_limit="-0.0698"/>
    <origin rpy="1.57079632679 0 0" xyz="0.0825 0 0"/>
    <parent link="panda_link3"/>
    <child link="panda_link4"/>
    <axis xyz="0 0 1"/>
    <limit effort="87" lower="-3.0718" upper="-0.0698" velocity="2.1750"/>
  </joint>
  <link name="panda_link5">
    <visual>
      <geometry>
        <mesh filename="franka_description/meshes/visual/link5.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="franka_description/meshes/collision/link5.stl"/>
      </geometry>
    </collision>
  </link>
  <joint name="panda_joint5" type="revolute">
    <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
    <origin rpy="-1.57079632679 0 0" xyz="-0.0825 0.384 0"/>
    <parent link="panda_link4"/>
    <child link="panda_link5"/>
    <axis xyz="0 0 1"/>
    <limit effort="12" lower="-2.8973" upper="2.8973" velocity="2.6100"/>
  </joint>
  <link name="panda_link6">
    <visual>
      <geometry>
        <mesh filename="franka_description/meshes/visual/link6.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="franka_description/meshes/collision/link6.stl"/>
      </geometry>
    </collision>
  </link>
  <joint name="panda_joint6" type="revolute">
    <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-0.0175" soft_upper_limit="3.7525"/>
    <origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
    <parent link="panda_link5"/>
    <child link="panda_link6"/>
    <axis xyz="0 0 1"/>
    <limit effort="12" lower="-0.0175" upper="3.7525" velocity="2.6100"/>
  </joint>
  <link name="panda_link7">
    <visual>
      <geometry>
        <mesh filename="franka_description/meshes/visual/link7.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="franka_description/meshes/collision/link7.stl"/>
      </geometry>
    </collision>
  </link>
  <joint name="panda_joint7" type="revolute">
    <safety_controller k_position="100.0" k_velocity="40.0" soft_lower_limit="-2.8973" soft_upper_limit="2.8973"/>
    <origin rpy="1.57079632679 0 0" xyz="0.088 0 0"/>
    <parent link="panda_link6"/>
    <child link="panda_link7"/>
    <axis xyz="0 0 1"/>
    <limit effort="12" lower="-2.8973" upper="2.8973" velocity="2.6100"/>
  </joint>
  <link name="panda_link8"/>
  <joint name="panda_joint8" type="fixed">
    <origin rpy="0 0 0" xyz="0 0 0.107"/>
    <parent link="panda_link7"/>
    <child link="panda_link8"/>
    <axis xyz="0 0 0"/>
  </joint>
  <joint name="panda_hand_joint" type="fixed">
    <parent link="panda_link8"/>
    <child link="panda_hand"/>
    <origin rpy="0 0 -0.785398163397" xyz="0 0 0"/>
  </joint>
  <link name="panda_hand">
    <visual>
      <geometry>
        <mesh filename="franka_description/meshes/visual/hand.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="franka_description/meshes/collision/hand.stl"/>
      </geometry>
    </collision>
  </link>
  <link name="panda_leftfinger">
    <visual>
      <geometry>
        <mesh filename="franka_description/meshes/visual/finger.dae"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <mesh filename="franka_description/meshes/collision/finger.stl"/>
      </geometry>
    </collision>
  </link>
  <link name="panda_rightfinger">
    <visual>
      <origin rpy="0 0 3.14159265359" xyz="0 0 0"/>
      <geometry>
        <mesh filename="franka_description/meshes/visual/finger.dae"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="0 0 3.14159265359" xyz="0 0 0"/>
      <geometry>
        <mesh filename="franka_description/meshes/collision/finger.stl"/>
      </geometry>
    </collision>
  </link>
  <joint name="panda_finger_joint1" type="prismatic">
    <parent link="panda_hand"/>
    <child link="panda_leftfinger"/>
    <origin rpy="0 0 0" xyz="0 0 0.0584"/>
    <axis xyz="0 1 0"/>
    <limit effort="20" lower="0.0" upper="0.04" velocity="0.2"/>
  </joint>
  <joint name="panda_finger_joint2" type="prismatic">
    <parent link="panda_hand"/>
    <child link="panda_rightfinger"/>
    <origin rpy="0 0 0" xyz="0 0 0.0584"/>
    <axis xyz="0 -1 0"/>
    <limit effort="20" lower="0.0" upper="0.04" velocity="0.2"/>
    <mimic joint="panda_finger_joint1"/>
  </joint>
</robot>
