modbus_test/urdf/fanucM16ib.urdf

175 lines
5.5 KiB
XML

<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from m16ib20.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="fanuc_m16ib20">
<link name="base_link">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../fanuc_m16ib_support/meshes/m16ib20/visual/base_link.stl"/>
</geometry>
<material name="">
<color rgba="0.96 0.76 0.13 1.0"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../fanuc_m16ib_support/meshes/m16ib20/collision/base_link.stl"/>
</geometry>
</collision>
</link>
<link name="link_1">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../fanuc_m16ib_support/meshes/m16ib20/visual/link_1.stl"/>
</geometry>
<material name="">
<color rgba="0.96 0.76 0.13 1.0"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../fanuc_m16ib_support/meshes/m16ib20/collision/link_1.stl"/>
</geometry>
</collision>
</link>
<link name="link_2">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../fanuc_m16ib_support/meshes/m16ib20/visual/link_2.stl"/>
</geometry>
<material name="">
<color rgba="0.96 0.76 0.13 1.0"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../fanuc_m16ib_support/meshes/m16ib20/collision/link_2.stl"/>
</geometry>
</collision>
</link>
<link name="link_3">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../fanuc_m16ib_support/meshes/m16ib20/visual/link_3.stl"/>
</geometry>
<material name="">
<color rgba="0.96 0.76 0.13 1.0"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../fanuc_m16ib_support/meshes/m16ib20/collision/link_3.stl"/>
</geometry>
</collision>
</link>
<link name="link_4">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../fanuc_m16ib_support/meshes/m16ib20/visual/link_4.stl"/>
</geometry>
<material name="">
<color rgba="0.96 0.76 0.13 1.0"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../fanuc_m16ib_support/meshes/m16ib20/collision/link_4.stl"/>
</geometry>
</collision>
</link>
<link name="link_5">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../fanuc_m16ib_support/meshes/m16ib20/visual/link_5.stl"/>
</geometry>
<material name="">
<color rgba="0.96 0.76 0.13 1.0"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../fanuc_m16ib_support/meshes/m16ib20/collision/link_5.stl"/>
</geometry>
</collision>
</link>
<link name="link_6">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../fanuc_m16ib_support/meshes/m16ib20/visual/link_6.stl"/>
</geometry>
<material name="">
<color rgba="0.15 0.15 0.15 1.0"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="../fanuc_m16ib_support/meshes/m16ib20/collision/link_6.stl"/>
</geometry>
</collision>
</link>
<link name="tool0"/>
<joint name="joint_1" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0.245"/>
<parent link="base_link"/>
<child link="link_1"/>
<axis xyz="0 0 1"/>
<limit effort="0" lower="-2.9671" upper="2.9671" velocity="2.8798"/>
</joint>
<joint name="joint_2" type="revolute">
<origin rpy="0 0 0" xyz="0.15 0.18759 0.28"/>
<parent link="link_1"/>
<child link="link_2"/>
<axis xyz="0 1 0"/>
<limit effort="0" lower="-1.5708" upper="2.7925" velocity="2.8798"/>
</joint>
<joint name="joint_3" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.18759 0.77"/>
<parent link="link_2"/>
<child link="link_3"/>
<axis xyz="0 -1 0"/>
<limit effort="0" lower="-2.9671" upper="5.0615" velocity="3.0543"/>
</joint>
<joint name="joint_4" type="revolute">
<origin rpy="0 0 0" xyz="0.18425 0 0.1"/>
<parent link="link_3"/>
<child link="link_4"/>
<axis xyz="-1 0 0"/>
<limit effort="0" lower="-3.4907" upper="3.4907" velocity="6.1087"/>
</joint>
<joint name="joint_5" type="revolute">
<origin rpy="0 0 0" xyz="0.55575 0 0"/>
<parent link="link_4"/>
<child link="link_5"/>
<axis xyz="0 -1 0"/>
<limit effort="0" lower="-2.4435" upper="2.4435" velocity="5.9341"/>
</joint>
<joint name="joint_6" type="revolute">
<origin rpy="0 0 0" xyz="0.1 0 0"/>
<parent link="link_5"/>
<child link="link_6"/>
<axis xyz="-1 0 0"/>
<limit effort="0" lower="-7.8540" upper="7.8540" velocity="9.0757"/>
</joint>
<joint name="joint_6-tool0" type="fixed">
<parent link="link_6"/>
<child link="tool0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
</robot>