samurai.urdf 10 KB
<?xml version="1.0"?>

<robot name="Samurai">
  
  <!-- *************************************************** -->
  <!-- ******************** Kinematics ******************* -->
  <!-- *************************************************** -->

  <link name="world"/>

  <joint name="theta1" type="continuous">
    <parent link="world"/>
    <child  link="link1"/>
    <origin xyz="0 0 0.6" rpy="0 0 0"/>
    <axis   xyz="0 0 1"/>
    <dynamics damping="0.5"/>
  </joint>

  <link name="link1"/>

  <joint name="theta2" type="continuous">
    <parent link="link1"/>
    <child  link="link2"/>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <axis   xyz="1 0 0"/>
    <dynamics damping="0.5"/>
  </joint>

  <link name="link2"/>

  <joint name="theta3" type="continuous">
    <parent link="link2"/>
    <child  link="link3"/>
    <origin xyz="0 0.4 0" rpy="0 0 0"/>
    <axis   xyz="1 0 0 "/>
    <dynamics damping="0.1"/>
  </joint>

  <link name="link3"/>

  <joint name="theta4" type="continuous">
    <parent link="link3"/>
    <child  link="link4"/>
    <origin xyz="0 0.4 0" rpy="0 0 0"/>
    <axis   xyz="0 1 0"/>
    <dynamics damping="0.02"/>
  </joint>

  <link name="link4"/>

  <joint name="theta5" type="continuous">
    <parent link="link4"/>
    <child  link="link5"/>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <axis   xyz="0 0 1"/>
    <dynamics damping="0.02"/>
  </joint>

  <link name="link5"/>

  <joint name="theta6" type="continuous">
    <parent link="link5"/>
    <child  link="link6"/>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <axis   xyz="1 0 0"/>
    <dynamics damping="0.02"/>
  </joint>

  <link name="link6"/>

  <joint name="holder" type="fixed">
    <parent link="link6"/>
    <child  link="katana"/>
    <origin xyz="0 0.1 0" rpy="-1.57079632679489661923 1.57079632679489661923 0"/>
  </joint>

  <link name="katana">
    <visual>
      <geometry>
        <mesh filename="package://cs133-final-robot/mesh/katana.dae"
          scale="0.25 0.25 0.25"/>
      </geometry>
    </visual>
  </link>

  <joint name="final" type="fixed">
    <parent link="katana"/>
    <child link="tip"/>
    <origin xyz="-0.01 0 0.275" rpy="0 0 3.141"/>
  </joint>

  <link name="tip">
  </link>


  <!-- *************************************************** -->
  <!-- ******************* RVIZ Colors ******************* -->
  <!-- *************************************************** -->

  <material name="white">    <color rgba="1.00 1.00 1.00 1"/>  </material>
  <material name="gray">     <color rgba="0.60 0.60 0.60 1"/>  </material>
  <material name="table">    <color rgba="0.85 0.77 0.77 1"/>  </material>
  <material name="black">    <color rgba="0.00 0.00 0.00 1"/>  </material>

  <material name="red">      <color rgba="1.00 0.00 0.00 1"/>  </material>
  <material name="green">    <color rgba="0.00 1.00 0.00 1"/>  </material>
  <material name="blue">     <color rgba="0.00 0.00 1.00 1"/>  </material>

  <material name="cyan">     <color rgba="0.00 1.00 1.00 1"/>  </material>
  <material name="magenta">  <color rgba="1.00 0.00 1.00 1"/>  </material>
  <material name="yellow">   <color rgba="1.00 1.00 0.00 1"/>  </material>

  <material name="orange">   <color rgba="1.00 0.65 0.00 1"/>  </material>


  <!-- *************************************************** -->
  <!-- ****** Building Blocks (Visual AND Inertial) ****** -->
  <!-- *************************************************** -->

  <!-- *** World-Fixed: Mount 1, Motor 1 *** -->

  <joint name="attach-mount1" type="fixed">
    <parent link="world"/>
    <child  link="mount1"/>
  </joint>
  <link name="mount1">
    <visual>
      <origin xyz="0 0 0.1" rpy="0 0 0"/>
      <geometry>
	<cylinder length="0.2" radius="0.02"/>
      </geometry>
      <material name="black"/>
    </visual>
    <inertial>
      <origin xyz="0 0 0.1" rpy="0 0 0"/>
      <mass value="0.2"/>
      <inertia
        ixx="0.000687" ixy="0.0" ixz="0.0"
        iyy="0.000687" iyz="0.0"
        izz="0.000040"/>
    </inertial>
  </link>

  <joint name="attach-motor1" type="fixed">
    <parent link="world"/>
    <child  link="motor1"/>
  </joint>
  <link name="motor1">
    <visual>
      <origin xyz="0 0 0.3" rpy="0 0 0"/>
      <geometry>
	<cylinder length="0.2" radius="0.05"/>
      </geometry>
      <material name="gray"/>
    </visual>
    <inertial>
      <origin xyz="0 0 0.3" rpy="0 0 0"/>
      <mass value="2.0"/>
      <inertia
        ixx="0.007917" ixy="0.0" ixz="0.0"
        iyy="0.007917" iyz="0.0"
        izz="0.002500"/>
    </inertial>
  </link>

  <!-- *** Motor 1 Output: Mount 2, Motor 2 *** -->

  <joint name="attach-mount2" type="fixed">
    <parent link="link1"/>
    <child  link="mount2"/>
  </joint>
  <link name="mount2">
    <visual>
      <origin xyz="0 0 -0.1" rpy="0 0 0"/>
      <geometry>
	<cylinder length="0.2" radius="0.02"/>
      </geometry>
      <material name="black"/>
    </visual>
    <inertial>
      <origin xyz="0 0 -0.1" rpy="0 0 0"/>
      <mass value="0.2"/>
      <inertia
        ixx="0.000687" ixy="0.0" ixz="0.0"
        iyy="0.000687" iyz="0.0"
        izz="0.000040"/>
    </inertial>
  </link>

  <joint name="attach-motor2" type="fixed">
    <parent link="link1"/>
    <child  link="motor2"/>
  </joint>
  <link name="motor2">
    <visual>
      <origin xyz="0 0 0" rpy="0 1.5708 0"/>
      <geometry>
	<cylinder length="0.2" radius="0.05"/>
      </geometry>
      <material name="gray"/>
    </visual>
    <inertial>
      <origin xyz="0 0 0" rpy="0 1.5708 0"/>
      <mass value="2.0"/>
      <inertia
        ixx="0.007917" ixy="0.0" ixz="0.0"
        iyy="0.007917" iyz="0.0"
        izz="0.002500"/>
    </inertial>
  </link>

  <!-- *** Motor 2 Output: Mount 3, Motor 3 *** -->

  <joint name="attach-mount3" type="fixed">
    <parent link="link2"/>
    <child  link="mount3"/>
  </joint>
  <link name="mount3">
    <visual>
      <origin xyz="0 0.2 0" rpy="1.5708 0 0"/>
      <geometry>
	<cylinder length="0.4" radius="0.02"/>
      </geometry>
      <material name="black"/>
    </visual>
    <inertial>
      <origin xyz="0 0.2 0" rpy="1.5708 0 0"/>
      <mass value="0.4"/>
      <inertia
        ixx="0.005373" ixy="0.0" ixz="0.0"
        iyy="0.005373" iyz="0.0"
        izz="0.000080"/>
    </inertial>
  </link>

  <joint name="attach-motor3" type="fixed">
    <parent link="link2"/>
    <child  link="motor3"/>
  </joint>
  <link name="motor3">
    <visual>
      <origin xyz="0 0.4 0" rpy="0 1.5708 0"/>
      <geometry>
	<cylinder length="0.2" radius="0.05"/>
      </geometry>
      <material name="gray"/>
    </visual>
    <inertial>
      <origin xyz="0 0.4 0" rpy="0 1.5708 0"/>
      <mass value="2.0"/>
      <inertia
        ixx="0.007917" ixy="0.0" ixz="0.0"
        iyy="0.007917" iyz="0.0"
        izz="0.002500"/>
    </inertial>
  </link>

  <!-- *** Motor 3 Output: Mount 4, Motor 4 *** -->

  <joint name="attach-mount4" type="fixed">
    <parent link="link3"/>
    <child  link="mount4"/>
  </joint>
  <link name="mount4">
    <visual>
      <origin xyz="0 0.1 0" rpy="1.5708 0 0"/>
      <geometry>
	<cylinder length="0.2" radius="0.02"/>
      </geometry>
      <material name="black"/>
    </visual>
    <inertial>
      <origin xyz="0 0.1 0" rpy="1.5708 0 0"/>
      <mass value="0.2"/>
      <inertia
        ixx="0.000687" ixy="0.0" ixz="0.0"
        iyy="0.000687" iyz="0.0"
        izz="0.000040"/>
    </inertial>
  </link>

  <joint name="attach-motor4" type="fixed">
    <parent link="link3"/>
    <child  link="motor4"/>
  </joint>
  <link name="motor4">
    <visual>
      <origin xyz="0 0.2 0" rpy="1.5708 0 0"/>
      <geometry>
	<cylinder length="0.1" radius="0.025"/>
      </geometry>
      <material name="gray"/>
    </visual>
    <inertial>
      <origin xyz="0 0.2 0" rpy="1.5708 0 0"/>
      <mass value="1.0"/>
      <inertia
        ixx="0.000990" ixy="0.0" ixz="0.0"
        iyy="0.000990" iyz="0.0"
        izz="0.000313"/>
    </inertial>
  </link>

  <!-- *** Motor 4 Output: Mount 5, Motor 5 *** -->

  <joint name="attach-mount5" type="fixed">
    <parent link="link4"/>
    <child  link="mount5"/>
  </joint>
  <link name="mount5">
    <visual>
      <origin xyz="0 -0.1 0" rpy="1.5708 0 0"/>
      <geometry>
	<cylinder length="0.2" radius="0.01"/>
      </geometry>
      <material name="black"/>
    </visual>
    <inertial>
      <origin xyz="0 -0.1 0" rpy="1.5708 0 0"/>
      <mass value="0.1"/>
      <inertia
        ixx="0.000336" ixy="0.0" ixz="0.0"
        iyy="0.000336" iyz="0.0"
        izz="0.000005"/>
    </inertial>
  </link>

  <joint name="attach-motor5" type="fixed">
    <parent link="link4"/>
    <child  link="motor5"/>
  </joint>
  <link name="motor5">
    <visual>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
	<cylinder length="0.1" radius="0.025"/>
      </geometry>
      <material name="gray"/>
    </visual>
    <inertial>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <mass value="1.0"/>
      <inertia
        ixx="0.000990" ixy="0.0" ixz="0.0"
        iyy="0.000990" iyz="0.0"
        izz="0.000313"/>
    </inertial>
  </link>

  <!-- *** Motor 5 Output: Motor 6 *** -->

  <joint name="attach-motor6" type="fixed">
    <parent link="link5"/>
    <child  link="motor6"/>
  </joint>
  <link name="motor6">
    <visual>
      <origin xyz="0 0 0" rpy="0 1.5708 0"/>
      <geometry>
	<cylinder length="0.1" radius="0.025"/>
      </geometry>
      <material name="gray"/>
    </visual>
    <inertial>
      <origin xyz="0 0 0" rpy="0 1.5708 0"/>
      <mass value="1.0"/>
      <inertia
        ixx="0.000990" ixy="0.0" ixz="0.0"
        iyy="0.000990" iyz="0.0"
        izz="0.000313"/>
    </inertial>
  </link>

  <!-- *** Motor 6 Output: Base, Palm, Fingers *** -->

  <joint name="attach-handbase" type="fixed">
    <parent link="link6"/>
    <child  link="handbase"/>
  </joint>
  <link name="handbase">
    <visual>
      <origin xyz="0 0.05 0" rpy="1.5708 0 0"/>
      <geometry>
	<cylinder length="0.1" radius="0.01"/>
      </geometry>
      <material name="black"/>
    </visual>
    <inertial>
      <origin xyz="0 0.05 0" rpy="1.5708 0 0"/>
      <mass value="0.05"/>
      <inertia
        ixx="0.000043" ixy="0.0" ixz="0.0"
        iyy="0.000043" iyz="0.0"
        izz="0.000003"/>
    </inertial>
  </link>

</robot>