216 lines
6.8 KiB
XML
216 lines
6.8 KiB
XML
<?xml version="1.0" ?>
|
|
<robot name="borunte">
|
|
<material name="Black">
|
|
<color rgba="0.1 0.1 0.1 0.99"/>
|
|
</material>
|
|
<material name="DarkRed">
|
|
<color rgba="0.5 0.0 0.0 0.99"/>
|
|
</material>
|
|
<!-- link list -->
|
|
<link name="base_link">
|
|
<visual>
|
|
<geometry>
|
|
<mesh filename="../urdf_support/borunte_support/meshes/base_link.stl"/>
|
|
</geometry>
|
|
<origin rpy="0.0 0 0.0" xyz="0 0 0"/>
|
|
<material name="Black"/>
|
|
</visual>
|
|
<collision>
|
|
<geometry>
|
|
<mesh filename="../urdf_support/borunte_support/meshes/base_link_collision.stl"/>
|
|
</geometry>
|
|
<origin rpy="0.0 0 0.0" xyz="0 0 0"/>
|
|
</collision>
|
|
</link>
|
|
<link name="link_1">
|
|
<visual>
|
|
<geometry>
|
|
<mesh filename="../urdf_support/borunte_support/meshes/link_1.stl"/>
|
|
</geometry>
|
|
<origin rpy="0.0 0 0.0" xyz="0 0 0"/>
|
|
<material name="DarkRed"/>
|
|
</visual>
|
|
<collision>
|
|
<geometry>
|
|
<mesh filename="../urdf_support/borunte_support/meshes/link_1_collision.stl"/>
|
|
</geometry>
|
|
<origin rpy="0.0 0 0.0" xyz="0 0 0"/>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="100"/>
|
|
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="link_2">
|
|
<visual>
|
|
<geometry>
|
|
<mesh filename="../urdf_support/borunte_support/meshes/link_2.stl"/>
|
|
</geometry>
|
|
<origin rpy="0.0 0 0.0" xyz="0 0 0"/>
|
|
<material name="DarkRed"/>
|
|
</visual>
|
|
<collision>
|
|
<geometry>
|
|
<mesh filename="../urdf_support/borunte_support/meshes/link_2_collision.stl"/>
|
|
</geometry>
|
|
<origin rpy="0.0 0 0.0" xyz="0 0 0"/>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="100"/>
|
|
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="link_3">
|
|
<visual>
|
|
<geometry>
|
|
<mesh filename="../urdf_support/borunte_support/meshes/link_3.stl"/>
|
|
</geometry>
|
|
<origin rpy="0.0 0 0.0" xyz="0 0.01 0"/>
|
|
<material name="DarkRed"/>
|
|
</visual>
|
|
<collision>
|
|
<geometry>
|
|
<mesh filename="../urdf_support/borunte_support/meshes/link_3_collision.stl"/>
|
|
</geometry>
|
|
<origin rpy="0.0 0 0.0" xyz="0 0.01 0"/>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="100"/>
|
|
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="link_4">
|
|
<visual>
|
|
<geometry>
|
|
<mesh filename="../urdf_support/borunte_support/meshes/link_4.stl"/>
|
|
</geometry>
|
|
<origin rpy="0.0 0.0 0.0" xyz="0 0 0"/>
|
|
<material name="DarkRed"/>
|
|
</visual>
|
|
<collision>
|
|
<geometry>
|
|
<mesh filename="../urdf_support/borunte_support/meshes/link_4_collision.stl"/>
|
|
</geometry>
|
|
<origin rpy="0.0 0 0.0" xyz="0 0 0"/>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="100"/>
|
|
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="link_5">
|
|
<visual>
|
|
<geometry>
|
|
<mesh filename="../urdf_support/borunte_support/meshes/link_5.stl"/>
|
|
</geometry>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<material name="DarkRed"/>
|
|
</visual>
|
|
<collision>
|
|
<geometry>
|
|
<mesh filename="../urdf_support/borunte_support/meshes/link_5_collision.stl"/>
|
|
</geometry>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="100"/>
|
|
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
|
</inertial>
|
|
</link>
|
|
<link name="link_6">
|
|
<visual>
|
|
<geometry>
|
|
<mesh filename="../urdf_support/borunte_support/meshes/link_6.stl"/>
|
|
</geometry>
|
|
<origin rpy="0 0 0.0" xyz="0 0 0"/>
|
|
<material name="DarkRed"/>
|
|
</visual>
|
|
<collision>
|
|
<geometry>
|
|
<mesh filename="../urdf_support/borunte_support/meshes/link_6_collision.stl"/>
|
|
</geometry>
|
|
<origin rpy="0 0 0.0" xyz="0 0 0"/>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="100"/>
|
|
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
|
</inertial>
|
|
</link>
|
|
<!-- joint list -->
|
|
<joint name="joint_1" type="revolute">
|
|
<limit effort="1000.0" lower="-3.076" upper="3.076" velocity="3.14"/>
|
|
<parent link="base_link"/>
|
|
<child link="link_1"/>
|
|
<axis xyz="0 0 1"/>
|
|
<origin rpy="0.0 0.0 0.0" xyz="0 0 0.24"/>
|
|
</joint>
|
|
<joint name="joint_2" type="revolute">
|
|
<!-- actual limit -1.74, reduced to reduce config problems -->
|
|
<limit effort="1000.0" lower="-1.0" upper="2.35" velocity="1.0"/>
|
|
<parent link="link_1"/>
|
|
<child link="link_2"/>
|
|
<axis xyz="0 1 0"/>
|
|
<origin rpy="0.0 0.0 0.0" xyz="0.07 0.09 0.165"/>
|
|
</joint>
|
|
<joint name="joint_3" type="revolute">
|
|
<limit effort="1000.0" lower="-2.094" upper="1.570" velocity="1.3"/>
|
|
<parent link="link_2"/>
|
|
<child link="link_3"/>
|
|
<axis xyz="0 1 0"/>
|
|
<origin rpy="0.0 1.5707963267948966 0.0" xyz="0.0 0.0 0.39"/>
|
|
</joint>
|
|
<joint name="joint_4" type="revolute">
|
|
<!-- actual limit +-2.094, reduced to reduce config problems -->
|
|
<limit effort="1000.0" lower="-1.5707963267948966" upper="1.5707963267948966" velocity="2.0"/>
|
|
<parent link="link_3"/>
|
|
<child link="link_4"/>
|
|
<axis xyz="0 0 1"/>
|
|
<origin rpy="0.0 0.0 0.0" xyz="-0.125 -0.09 0.075"/>
|
|
</joint>
|
|
<joint name="joint_5" type="revolute">
|
|
<limit effort="1000.0" lower="-1.919" upper="2.094" velocity="2.35"/>
|
|
<parent link="link_4"/>
|
|
<child link="link_5"/>
|
|
<axis xyz="0 1 0"/>
|
|
<origin rpy="0.0 0.0 0.0" xyz="0.0 -0.0 0.31"/>
|
|
</joint>
|
|
<joint name="joint_6" type="revolute">
|
|
<limit effort="1000.0" lower="-3.141592653589793" upper="3.141592653589793" velocity="2.35"/>
|
|
<parent link="link_5"/>
|
|
<child link="link_6"/>
|
|
<axis xyz="0 0 1"/>
|
|
<origin rpy="0.0 0.0 0.0" xyz="0 0 0.104"/>
|
|
</joint>
|
|
<!-- ROS-Industrial 'base' frame: 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"/>
|
|
<axis xyz="0 0 1"/>
|
|
<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.015"/>
|
|
<parent link="link_6"/>
|
|
<child link="flange"/>
|
|
</joint>
|
|
<!-- ROS-Industrial 'tool0' frame: all-zeros tool frame -->
|
|
<link name="tool0"/>
|
|
<joint name="flange-tool0" type="fixed">
|
|
<!-- marker -->
|
|
<origin rpy="0 3.141592653589793 0" xyz="0 0 0"/>
|
|
<parent link="flange"/>
|
|
<child link="tool0"/>
|
|
</joint>
|
|
<!-- 'world' frame: default pose reference frame -->
|
|
<link name="world"/>
|
|
<joint name="world-base_link" type="fixed">
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<axis xyz="0 0 1"/>
|
|
<child link="world"/>
|
|
<parent link="base_link"/>
|
|
</joint>
|
|
</robot>
|