123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418 |
- <?xml version="1.0" encoding="utf-8"?>
- <!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com)
- Commit Version: 1.6.0-4-g7f85cfe Build Version: 1.6.7995.38578
- For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
- <robot
- name="fanuc_m10ia_11">
- <link name="world_link" />
- <joint name="world_joint" type="fixed">
- <parent link="world_link" />
- <child link="base_link" />
- <origin xyz="0 0 2.17" rpy="0 3.14 0" />
- </joint>
- <link
- name="base_link">
- <inertial>
- <origin
- xyz="0.012984 0.00048961 0.12327"
- rpy="0 0 0" />
- <mass
- value="13.511" />
- <inertia
- ixx="0.1373"
- ixy="0.00087636"
- ixz="0.003867"
- iyy="0.14276"
- iyz="4.9465E-05"
- izz="0.11338" />
- </inertial>
- <visual>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://fanuc_m10ia_11/meshes/base_link.STL" />
- </geometry>
- <material
- name="">
- <color
- rgba="0.26667 0.26667 0.26667 1" />
- </material>
- </visual>
- <collision>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://fanuc_m10ia_11/meshes/base_link.STL" />
- </geometry>
- </collision>
- </link>
- <link
- name="link1">
- <inertial>
- <origin
- xyz="0.046379 0.040259 0.11802"
- rpy="0 0 0" />
- <mass
- value="10.873" />
- <inertia
- ixx="0.1054"
- ixy="-0.0045186"
- ixz="-0.021996"
- iyy="0.13842"
- iyz="-0.018604"
- izz="0.12811" />
- </inertial>
- <visual>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://fanuc_m10ia_11/meshes/link1.STL" />
- </geometry>
- <material
- name="">
- <color
- rgba="1 1 0 1" />
- </material>
- </visual>
- <collision>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://fanuc_m10ia_11/meshes/link1.STL" />
- </geometry>
- </collision>
- </link>
- <joint
- name="joint1"
- type="revolute">
- <origin
- xyz="0.0064875 6.5871E-05 0.273"
- rpy="0 0 0" />
- <parent
- link="base_link" />
- <child
- link="link1" />
- <axis
- xyz="0 0 1" />
- <limit
- lower="-2.9671"
- upper="2.9671"
- effort="0"
- velocity="3.49" />
- </joint>
- <link
- name="link2">
- <inertial>
- <origin
- xyz="0.05291 0.17755 -0.048961"
- rpy="0 0 0" />
- <mass
- value="36.602" />
- <inertia
- ixx="11.349"
- ixy="-5.226"
- ixz="-0.2569"
- iyy="4.0762"
- iyz="-0.25187"
- izz="15.125" />
- </inertial>
- <visual>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://fanuc_m10ia_11/meshes/link2.STL" />
- </geometry>
- <material
- name="">
- <color
- rgba="1 1 0 1" />
- </material>
- </visual>
- <collision>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://fanuc_m10ia_11/meshes/link2.STL" />
- </geometry>
- </collision>
- </link>
- <joint
- name="joint2"
- type="revolute">
- <origin
- xyz="0.14975 -0.042266 0.172"
- rpy="1.5708 0 0" />
- <parent
- link="link1" />
- <child
- link="link2" />
- <axis
- xyz="0 0 1" />
- <limit
- lower="-1.6581"
- upper="2.7925"
- effort="0"
- velocity="3.49" />
- </joint>
- <link
- name="link3">
- <inertial>
- <origin
- xyz="0.079158 -0.087511 0.069201"
- rpy="0 0 0" />
- <mass
- value="5.3113" />
- <inertia
- ixx="0.037702"
- ixy="0.0082399"
- ixz="-0.001985"
- iyy="0.020224"
- iyz="0.0023782"
- izz="0.038051" />
- </inertial>
- <visual>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://fanuc_m10ia_11/meshes/link3.STL" />
- </geometry>
- <material
- name="">
- <color
- rgba="1 1 0 1" />
- </material>
- </visual>
- <collision>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://fanuc_m10ia_11/meshes/link3.STL" />
- </geometry>
- </collision>
- </link>
- <joint
- name="joint3"
- type="revolute">
- <origin
- xyz="0.0027653 0.79224 0.0203"
- rpy="3.1416 0 0" />
- <parent
- link="link2" />
- <child
- link="link3" />
- <axis
- xyz="0 0 1" />
- <limit
- lower="-3.2289"
- upper="4.8346"
- effort="0"
- velocity="3.67" />
- </joint>
- <link
- name="link4">
- <inertial>
- <origin
- xyz="0.033387 -0.00015103 0.47587"
- rpy="0 0 0" />
- <mass
- value="6.9067" />
- <inertia
- ixx="0.43369"
- ixy="0.00010105"
- ixz="-0.04807"
- iyy="0.43976"
- iyz="0.00052043"
- izz="0.019367" />
- </inertial>
- <visual>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://fanuc_m10ia_11/meshes/link4.STL" />
- </geometry>
- <material
- name="">
- <color
- rgba="1 1 0 1" />
- </material>
- </visual>
- <collision>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://fanuc_m10ia_11/meshes/link4.STL" />
- </geometry>
- </collision>
- </link>
- <joint
- name="joint4"
- type="revolute">
- <origin
- xyz="0.18173 -0.18635 0.062125"
- rpy="0 1.5708 0" />
- <parent
- link="link3" />
- <child
- link="link4" />
- <axis
- xyz="0 0 1" />
- <limit
- lower="-3.4907"
- upper="3.4907"
- effort="0"
- velocity="7.50" />
- </joint>
- <link
- name="link5">
- <inertial>
- <origin
- xyz="-1.032 0.80245 0.052761"
- rpy="0 0 0" />
- <mass
- value="36.602" />
- <inertia
- ixx="11.349"
- ixy="5.226"
- ixz="0.2569"
- iyy="4.0762"
- iyz="-0.25187"
- izz="15.125" />
- </inertial>
- <visual>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://fanuc_m10ia_11/meshes/link5.STL" />
- </geometry>
- <material
- name="">
- <color
- rgba="1 1 0 1" />
- </material>
- </visual>
- <collision>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://fanuc_m10ia_11/meshes/link5.STL" />
- </geometry>
- </collision>
- </link>
- <joint
- name="joint5"
- type="revolute">
- <origin
- xyz="0.045625 -0.0014127 0.90042"
- rpy="0 -1.5708 0" />
- <parent
- link="link4" />
- <child
- link="link5" />
- <axis
- xyz="0 0 1" />
- <limit
- lower="-2.4435"
- upper="2.4435"
- effort="0"
- velocity="7.50" />
- </joint>
- <link
- name="link6">
- <inertial>
- <origin
- xyz="-0.80245 -0.0067605 -1.1271"
- rpy="0 0 0" />
- <mass
- value="36.602" />
- <inertia
- ixx="4.0762"
- ixy="-0.25187"
- ixz="-5.226"
- iyy="15.125"
- iyz="-0.2569"
- izz="11.349" />
- </inertial>
- <visual>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://fanuc_m10ia_11/meshes/link6.STL" />
- </geometry>
- <material
- name="">
- <color
- rgba="0.098 0.098 0.098 1" />
- </material>
- </visual>
- <collision>
- <origin
- xyz="0 0 0"
- rpy="0 0 0" />
- <geometry>
- <mesh
- filename="package://fanuc_m10ia_11/meshes/link6.STL" />
- </geometry>
- </collision>
- </link>
- <joint
- name="joint6"
- type="revolute">
- <origin
- xyz="0.095084 0 0.046"
- rpy="-1.5708 0 -1.5708" />
- <parent
- link="link5" />
- <child
- link="link6" />
- <axis
- xyz="0 0 1" />
- <limit
- lower="-4.7124"
- upper="4.7124"
- effort="0"
- velocity="11.00" />
- </joint>
- <link name="ee_link" />
- <joint name="ee_joint" type="fixed">
- <parent link="link6" />
- <child link="ee_link" />
- <origin xyz="0.051 0.1209 0.3107" rpy="0 0 0" />
- </joint>
- <link name="tool_link" />
- <joint name="tool_joint" type="fixed">
- <parent link="ee_link" />
- <child link="tool_link" />
- <origin xyz="0 0 0.004" rpy="0 0 0" />
- </joint>
- </robot>
|