192 lines
6.2 KiB
XML
192 lines
6.2 KiB
XML
<?xml version="1.0" ?>
|
|
<!-- =================================================================================== -->
|
|
<!-- | This document was autogenerated by xacro from lrmate200ib.xacro | -->
|
|
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
|
<!-- =================================================================================== -->
|
|
<robot name="fanuc_lrmate200ib">
|
|
<!-- links: main serial chain -->
|
|
<link name="base_link">
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="../fanuc_lrmate200ib_support/meshes/lrmate200ib/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_lrmate200ib_support/meshes/lrmate200ib/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_lrmate200ib_support/meshes/lrmate200ib/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_lrmate200ib_support/meshes/lrmate200ib/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_lrmate200ib_support/meshes/lrmate200ib/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_lrmate200ib_support/meshes/lrmate200ib/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_lrmate200ib_support/meshes/lrmate200ib/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_lrmate200ib_support/meshes/lrmate200ib/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_lrmate200ib_support/meshes/lrmate200ib/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_lrmate200ib_support/meshes/lrmate200ib/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_lrmate200ib_support/meshes/lrmate200ib/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_lrmate200ib_support/meshes/lrmate200ib/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_lrmate200ib_support/meshes/lrmate200ib/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_lrmate200ib_support/meshes/lrmate200ib/collision/link_6.stl"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<!-- joints: main serial chain -->
|
|
<joint name="joint_1" type="revolute">
|
|
<origin rpy="0 0 0" xyz="0 0 0.350"/>
|
|
<parent link="base_link"/>
|
|
<child link="link_1"/>
|
|
<axis xyz="0 0 1"/>
|
|
<limit effort="0" lower="-2.7925" upper="2.7925" velocity="3.1415"/>
|
|
</joint>
|
|
<joint name="joint_2" type="revolute">
|
|
<origin rpy="0 0 0" xyz="0.150 0 0"/>
|
|
<parent link="link_1"/>
|
|
<child link="link_2"/>
|
|
<axis xyz="0 1 0"/>
|
|
<limit effort="0" lower="-0.5759" upper="2.6529" velocity="3.1415"/>
|
|
</joint>
|
|
<joint name="joint_3" type="revolute">
|
|
<origin rpy="0 0 0" xyz="0 0 0.250"/>
|
|
<parent link="link_2"/>
|
|
<child link="link_3"/>
|
|
<axis xyz="0 -1 0"/>
|
|
<limit effort="0" lower="-2.6145" upper="2.8797" velocity="3.9269"/>
|
|
</joint>
|
|
<joint name="joint_4" type="revolute">
|
|
<origin rpy="0 0 0" xyz="0 0 0.075"/>
|
|
<parent link="link_3"/>
|
|
<child link="link_4"/>
|
|
<axis xyz="-1 0 0"/>
|
|
<limit effort="0" lower="-3.3161" upper="3.3161" velocity="6.9813"/>
|
|
</joint>
|
|
<joint name="joint_5" type="revolute">
|
|
<origin rpy="0 0 0" xyz="0.290 0 0"/>
|
|
<parent link="link_4"/>
|
|
<child link="link_5"/>
|
|
<axis xyz="0 -1 0"/>
|
|
<limit effort="0" lower="-2.0943" upper="2.0943" velocity="5.7595"/>
|
|
</joint>
|
|
<joint name="joint_6" type="revolute">
|
|
<origin rpy="0 0 0" xyz="0.080 0 0"/>
|
|
<parent link="link_5"/>
|
|
<child link="link_6"/>
|
|
<axis xyz="-1 0 0"/>
|
|
<limit effort="0" lower="-6.2831" upper="6.2831" velocity="8.3775"/>
|
|
</joint>
|
|
<!-- ROS base_link to Fanuc World Coordinates transform -->
|
|
<link name="base"/>
|
|
<joint name="base_link-base" type="fixed">
|
|
<origin rpy="0 0 0" xyz="0 0 0.350"/>
|
|
<parent link="base_link"/>
|
|
<child link="base"/>
|
|
</joint>
|
|
<!-- ROS-Industrial 'flange' frame: attachment point for EEF models -->
|
|
<link name="flange"/>
|
|
<joint name="joint_6-flange" type="fixed">
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<parent link="link_6"/>
|
|
<child link="flange"/>
|
|
</joint>
|
|
<!-- ROS-Industrial 'tool0' frame: all-zeros tool frame -->
|
|
<link name="tool0"/>
|
|
<joint name="link_6-tool0" type="fixed">
|
|
<origin rpy="3.14159265359 -1.57079632679 0" xyz="0 0 0"/>
|
|
<parent link="link_6"/>
|
|
<child link="tool0"/>
|
|
</joint>
|
|
</robot>
|