bullet3/data/kuka_lwr/kuka.urdf
2015-08-19 16:05:32 -07:00

265 lines
9.6 KiB
XML

<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from kuka_lwr_arm.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="kuka_lwr">
<!-- right is either 1 (for right arm) or -1 (for left arm) -->
<link name="calib_kuka_arm_base_link">
<inertial>
<mass value="0"/>
<!-- static base, disable dynamics for this link -->
<origin rpy="0 0 0" xyz="0 0 0.055"/>
<inertia ixx="0.00381666666667" ixy="0" ixz="0" iyy="0.0036" iyz="0" izz="0.00381666666667"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes_arm/arm_base.stl"/>
</geometry>
<material name="Orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes_arm/convex/arm_base_convex.stl"/>
</geometry>
</collision>
</link>
<joint name="kuka_arm_0_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0.11"/>
<axis xyz="0 0 1"/>
<limit effort="204" lower="-2.96705972839" upper="2.96705972839" velocity="1.91986217719"/>
<dynamics damping="0.1"/>
<parent link="calib_kuka_arm_base_link"/>
<child link="kuka_arm_1_link"/>
</joint>
<link name="kuka_arm_1_link">
<inertial>
<mass value="2.0"/>
<origin rpy="0 0 0" xyz="0 0.04 0.130"/>
<inertia ixx="0.0136666666667" ixy="0" ixz="0" iyy="0.0118666666667" iyz="0" izz="0.003"/>
</inertial>
<visual>
<origin rpy="0 0 3.14159265359" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes_arm/arm_segment_a.stl"/>
</geometry>
<material name="Orange"/>
</visual>
<collision>
<origin rpy="0 0 3.14159265359" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes_arm/convex/arm_segment_a_convex.stl"/>
</geometry>
</collision>
</link>
<transmission name="kuka_arm_0_trans" type="pr2_mechanism_model/SimpleTransmission">
<actuator name="kuka_arm_0_motor"/>
<joint name="kuka_arm_0_joint"/>
<mechanicalReduction>1.0</mechanicalReduction>
</transmission>
<joint name="kuka_arm_1_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0.20"/>
<axis xyz="0 -1 0"/>
<!--limit lower="${-120 * M_PI / 180}" upper="${120 * M_PI / 180}"
effort="306" velocity="${arm_velocity_scale_factor * 110 * M_PI / 180}" /-->
<!-- nalt: Reduced limits to avoid contact with table - kinda hacky, should not be done here -->
<limit effort="306" lower="-1.57079632679" upper="1.57079632679" velocity="1.91986217719"/>
<dynamics damping="0.1"/>
<parent link="kuka_arm_1_link"/>
<child link="kuka_arm_2_link"/>
</joint>
<link name="kuka_arm_2_link">
<inertial>
<mass value="2.0"/>
<origin rpy="0 0 0" xyz="0 -0.04 0.07"/>
<inertia ixx="0.0136666666667" ixy="0" ixz="0" iyy="0.0118666666667" iyz="0" izz="0.003"/>
</inertial>
<visual>
<origin rpy="3.14159265359 0 3.14159265359" xyz="0 0 0.2"/>
<geometry>
<mesh filename="meshes_arm/arm_segment_b.stl"/>
</geometry>
<material name="Orange"/>
</visual>
<collision>
<origin rpy="3.14159265359 0 3.14159265359" xyz="0 0 0.2"/>
<geometry>
<mesh filename="meshes_arm/convex/arm_segment_b_convex.stl"/>
</geometry>
</collision>
</link>
<transmission name="kuka_arm_1_trans" type="pr2_mechanism_model/SimpleTransmission">
<actuator name="kuka_arm_1_motor"/>
<joint name="kuka_arm_1_joint"/>
<mechanicalReduction>1.0</mechanicalReduction>
</transmission>
<joint name="kuka_arm_2_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0.20"/>
<axis xyz="0 0 1"/>
<limit effort="204" lower="-2.96705972839" upper="2.96705972839" velocity="2.26892802759"/>
<dynamics damping="0.1"/>
<parent link="kuka_arm_2_link"/>
<child link="kuka_arm_3_link"/>
</joint>
<link name="kuka_arm_3_link">
<inertial>
<mass value="2.0"/>
<origin rpy="0 0 0" xyz="0 -0.04 0.130"/>
<inertia ixx="0.0136666666667" ixy="0" ixz="0" iyy="0.0118666666667" iyz="0" izz="0.003"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes_arm/arm_segment_a.stl"/>
</geometry>
<material name="Orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes_arm/convex/arm_segment_a_convex.stl"/>
</geometry>
</collision>
</link>
<transmission name="kuka_arm_2_trans" type="pr2_mechanism_model/SimpleTransmission">
<actuator name="kuka_arm_2_motor"/>
<joint name="kuka_arm_2_joint"/>
<mechanicalReduction>1.0</mechanicalReduction>
</transmission>
<joint name="kuka_arm_3_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0.20"/>
<axis xyz="0 1 0"/>
<limit effort="306" lower="-2.09439510239" upper="2.09439510239" velocity="2.26892802759"/>
<dynamics damping="0.1"/>
<parent link="kuka_arm_3_link"/>
<child link="kuka_arm_4_link"/>
</joint>
<link name="kuka_arm_4_link">
<inertial>
<mass value="2.0"/>
<origin rpy="0 0 0" xyz="0 0.04 0.07"/>
<inertia ixx="0.0136666666667" ixy="0" ixz="0" iyy="0.0118666666667" iyz="0" izz="0.003"/>
</inertial>
<visual>
<origin rpy="0 3.14159265359 3.14159265359" xyz="0 0 0.2"/>
<geometry>
<mesh filename="meshes_arm/arm_segment_b.stl"/>
</geometry>
<material name="Orange"/>
</visual>
<collision>
<origin rpy="0 3.14159265359 3.14159265359" xyz="0 0 0.2"/>
<geometry>
<mesh filename="meshes_arm/convex/arm_segment_b_convex.stl"/>
</geometry>
</collision>
</link>
<transmission name="kuka_arm_3_trans" type="pr2_mechanism_model/SimpleTransmission">
<actuator name="kuka_arm_3_motor"/>
<joint name="kuka_arm_3_joint"/>
<mechanicalReduction>1.0</mechanicalReduction>
</transmission>
<joint name="kuka_arm_4_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0.20"/>
<axis xyz="0 0 1"/>
<limit effort="204" lower="-2.96705972839" upper="2.96705972839" velocity="2.26892802759"/>
<dynamics damping="0.1"/>
<parent link="kuka_arm_4_link"/>
<child link="kuka_arm_5_link"/>
</joint>
<link name="kuka_arm_5_link">
<inertial>
<mass value="2.0"/>
<origin rpy="0 0 0" xyz="0 0.02 0.124"/>
<inertia ixx="0.0126506666667" ixy="0" ixz="0" iyy="0.0108506666667" iyz="0" izz="0.003"/>
</inertial>
<visual>
<origin rpy="0 0 3.14159265359" xyz="0 0 0"/>
<geometry name="kuka_arm_5_geom">
<mesh filename="meshes_arm/arm_segment_last.stl"/>
</geometry>
<material name="Orange"/>
</visual>
<collision>
<origin rpy="0 0 3.14159265359" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes_arm/convex/arm_segment_last_convex.stl"/>
</geometry>
</collision>
</link>
<transmission name="kuka_arm_4_trans" type="pr2_mechanism_model/SimpleTransmission">
<actuator name="kuka_arm_4_motor"/>
<joint name="kuka_arm_4_joint"/>
<mechanicalReduction>1.0</mechanicalReduction>
</transmission>
<joint name="kuka_arm_5_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0.19"/>
<axis xyz="0 -1 0"/>
<limit effort="306" lower="-2.09439510239" upper="2.09439510239" velocity="3.14159265359"/>
<dynamics damping="0.1"/>
<parent link="kuka_arm_5_link"/>
<child link="kuka_arm_6_link"/>
</joint>
<link name="kuka_arm_6_link">
<inertial>
<mass value="2.0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.00520833333333" ixy="0" ixz="0" iyy="0.00520833333333" iyz="0" izz="0.00520833333333"/>
</inertial>
<visual>
<origin rpy="0 0 3.14159265359" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes_arm/arm_wrist.stl"/>
</geometry>
<material name="Grey"/>
</visual>
<collision>
<origin rpy="0 0 3.14159265359" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes_arm/convex/arm_wrist_convex.stl"/>
</geometry>
</collision>
</link>
<transmission name="kuka_arm_5_trans" type="pr2_mechanism_model/SimpleTransmission">
<actuator name="kuka_arm_5_motor"/>
<joint name="kuka_arm_5_joint"/>
<mechanicalReduction>1.0</mechanicalReduction>
</transmission>
<joint name="kuka_arm_6_joint" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0.078"/>
<axis xyz="0 0 1"/>
<limit effort="204" lower="-2.96705972839" upper="2.96705972839" velocity="3.14159265359"/>
<dynamics damping="0.1"/>
<parent link="kuka_arm_6_link"/>
<child link="kuka_arm_7_link"/>
</joint>
<link name="kuka_arm_7_link">
<inertial>
<mass value="2.0"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.000833333333333" ixy="0" ixz="0" iyy="0.000833333333333" iyz="0" izz="0.000833333333333"/>
</inertial>
<visual>
<origin rpy="0 0 3.14159265359" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes_arm/arm_flanche.stl"/>
</geometry>
<material name="Grey"/>
</visual>
<collision>
<origin rpy="0 0 3.14159265359" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes_arm/convex/arm_flanche_convex.stl"/>
</geometry>
</collision>
</link>
<transmission name="kuka_arm_6_trans" type="pr2_mechanism_model/SimpleTransmission">
<actuator name="kuka_arm_6_motor"/>
<joint name="kuka_arm_6_joint"/>
<mechanicalReduction>1.0</mechanicalReduction>
</transmission>
</robot>