Last active
February 27, 2023 19:09
-
-
Save MightyMirko/58fa382c733f8555cbf86055a3ad49f4 to your computer and use it in GitHub Desktop.
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
<?xml version="1.0"?> | |
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"> | |
<!-- some constants --> | |
<xacro:property name="PI" value="3.1415926535897931" /> | |
<xacro:property name="joint_damping" value="10.0" /> | |
<xacro:property name="joint_friction" value="0.1" /> | |
<xacro:property name="max_effort" value="300" /> | |
<xacro:property name="max_velocity" value="10" /> | |
<!-- TODO: move modes to args, decouple urdf/gazebo/controls --> | |
<!-- includes --> | |
<!-- <xacro:include filename="$(find lbr_description)/urdf/materials.urdf.xacro"/> --> | |
<!-- <xacro:include filename="$(find lbr_description)/gazebo/iiwa.gazebo.xacro"/> --> | |
<!-- <xacro:include filename="$(find lbr_description)/ros2_control/lbr.ros2_control.xacro"/> --> | |
<material name="orange"> | |
<color rgba="0.5 0.5 0.5 1.0" /> | |
</material> | |
<material name="silver"> | |
<color rgba="0.5 0.5 0.5 1.0" /> | |
</material> | |
<!-- robot as extracted via https://github.com/syuntoku14/fusion2urdf --> | |
<xacro:macro name="iiwa14" params="parent prefix *origin"> | |
<link name="${prefix}iiwa_base" type="fixed" /> | |
<joint name="${prefix}iiwa_root_joint" type="fixed"> | |
<xacro:insert_block name="origin" /> | |
<parent link="${parent}" /> | |
<child link="${prefix}iiwa_base" /> | |
</joint> | |
<joint name="${prefix}iiwa_base_joint" type="fixed"> | |
<origin rpy="0.0 0 0" xyz="0 0 0" /> | |
<parent link="${prefix}iiwa_base" /> | |
<child link="${prefix}link_0" /> | |
</joint> | |
<link name="${prefix}link_0"> | |
<inertial> | |
<origin rpy="0 0 0" | |
xyz="-0.01283618494463161 4.904567390585061e-08 0.07010682239932087" /> | |
<mass value="4.861279" /> | |
<inertia ixx="0.017901" ixy="0.000000" ixz="0.000771" iyy="0.022356" iyz="-0.000000" | |
izz="0.021346" /> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="0 0 0" /> | |
<geometry> | |
<mesh filename="package://lbr_description/meshes/iiwa7/visual/link_0.stl" /> | |
</geometry> | |
<material name="silver" /> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0 0 0" /> | |
<geometry> | |
<mesh filename="package://lbr_description/meshes/iiwa7/collision/link_0.stl" /> | |
</geometry> | |
</collision> | |
</link> | |
<link name="${prefix}link_1"> | |
<inertial> | |
<origin rpy="0 0 0" | |
xyz="4.9980243666546455e-08 -0.0347335291089292 0.12351608478142942" /> | |
<mass value="3.400745" /> | |
<inertia ixx="0.021502" ixy="-0.000000" ixz="0.000000" iyy="0.020512" iyz="0.003828" | |
izz="0.007587" /> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="-0.0 0.0 -0.1475" /> | |
<geometry> | |
<mesh filename="package://lbr_description/meshes/iiwa7/visual/link_1.stl" /> | |
</geometry> | |
<material name="orange" /> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="-0.0 0.0 -0.1475" /> | |
<geometry> | |
<mesh filename="package://lbr_description/meshes/iiwa7/collision/link_1.stl" /> | |
</geometry> | |
</collision> | |
</link> | |
<link name="${prefix}link_2"> | |
<inertial> | |
<origin rpy="0 0 0" | |
xyz="4.0558428502019873e-08 0.04491581578298656 0.06732515284873997" /> | |
<mass value="3.430184" /> | |
<inertia ixx="0.021455" ixy="-0.000000" ixz="0.000000" iyy="0.020444" iyz="0.003570" | |
izz="0.007671" /> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="0.0 0.0105 -0.3405" /> | |
<geometry> | |
<mesh filename="package://lbr_description/meshes/iiwa7/visual/link_2.stl" /> | |
</geometry> | |
<material name="orange" /> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0.0 0.0105 -0.3405" /> | |
<geometry> | |
<mesh filename="package://lbr_description/meshes/iiwa7/collision/link_2.stl" /> | |
</geometry> | |
</collision> | |
</link> | |
<link name="${prefix}link_3"> | |
<inertial> | |
<origin rpy="0 0 0" | |
xyz="-5.881068064938613e-09 0.02956361869175564 0.1365034185434154" /> | |
<mass value="3.995443" /> | |
<inertia ixx="0.031559" ixy="-0.000000" ixz="0.000000" iyy="0.029960" | |
iyz="-0.006133" izz="0.009574" /> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="0.0 0.0 -0.515" /> | |
<geometry> | |
<mesh filename="package://lbr_description/meshes/iiwa7/visual/link_3.stl" /> | |
</geometry> | |
<material name="orange" /> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0.0 0.0 -0.515" /> | |
<geometry> | |
<mesh filename="package://lbr_description/meshes/iiwa7/collision/link_3.stl" /> | |
</geometry> | |
</collision> | |
</link> | |
<link name="${prefix}link_4"> | |
<inertial> | |
<origin rpy="0 0 0" | |
xyz="-4.1344813497116265e-08 -0.044916218629510306 0.06732501840381" /> | |
<mass value="3.430182" /> | |
<inertia ixx="0.021454" ixy="0.000000" ixz="-0.000000" iyy="0.020443" | |
iyz="-0.003570" izz="0.007670" /> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="0.0 -0.0105 -0.7405" /> | |
<geometry> | |
<mesh filename="package://lbr_description/meshes/iiwa7/visual/link_4.stl" /> | |
</geometry> | |
<material name="orange" /> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0.0 -0.0105 -0.7405" /> | |
<geometry> | |
<mesh filename="package://lbr_description/meshes/iiwa7/collision/link_4.stl" /> | |
</geometry> | |
</collision> | |
</link> | |
<link name="${prefix}link_5"> | |
<inertial> | |
<origin rpy="0 0 0" | |
xyz="2.416002990197734e-08 -0.021386601078580914 0.085468591256322" /> | |
<mass value="2.131557" /> | |
<inertia ixx="0.012684" ixy="-0.000000" ixz="-0.000000" iyy="0.010952" | |
iyz="0.003889" izz="0.005624" /> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="0.0 0.0 -0.915" /> | |
<geometry> | |
<mesh filename="package://lbr_description/meshes/iiwa7/visual/link_5.stl" /> | |
</geometry> | |
<material name="orange" /> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0.0 0.0 -0.915" /> | |
<geometry> | |
<mesh filename="package://lbr_description/meshes/iiwa7/collision/link_5.stl" /> | |
</geometry> | |
</collision> | |
</link> | |
<link name="${prefix}link_6"> | |
<inertial> | |
<origin rpy="0 0 0" | |
xyz="-9.07120004240837e-08 0.0709871260349443 0.002115721730276743" /> | |
<mass value="2.311862" /> | |
<inertia ixx="0.006412" ixy="-0.000000" ixz="-0.000000" iyy="0.006166" | |
iyz="0.000314" izz="0.004459" /> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="0.0 0.0707 -1.1405" /> | |
<geometry> | |
<mesh filename="package://lbr_description/meshes/iiwa7/visual/link_6.stl" /> | |
</geometry> | |
<material name="orange" /> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0.0 0.0707 -1.1405" /> | |
<geometry> | |
<mesh filename="package://lbr_description/meshes/iiwa7/collision/link_6.stl" /> | |
</geometry> | |
</collision> | |
</link> | |
<link name="${prefix}link_7"> | |
<inertial> | |
<origin rpy="0 0 0" | |
xyz="4.535378460217862e-06 -1.7615872956281168e-08 0.009883270430701696" /> | |
<mass value="0.338747" /> | |
<inertia ixx="0.000250" ixy="-0.000000" ixz="-0.000000" iyy="0.000245" | |
iyz="0.000000" izz="0.000406" /> | |
</inertial> | |
<visual> | |
<origin rpy="0 0 0" xyz="0.0 0.0002 -1.2314" /> | |
<geometry> | |
<mesh filename="package://lbr_description/meshes/iiwa7/visual/link_7.stl" /> | |
</geometry> | |
<material name="silver" /> | |
</visual> | |
<collision> | |
<origin rpy="0 0 0" xyz="0.0 0.0002 -1.2314" /> | |
<geometry> | |
<mesh filename="package://lbr_description/meshes/iiwa7/collision/link_7.stl" /> | |
</geometry> | |
</collision> | |
</link> | |
<link name="${prefix}tool0"> | |
</link> | |
<joint name="${prefix}joint_a1" type="revolute"> | |
<origin rpy="0 0 0" xyz="0.0 0.0 0.1475" /> | |
<parent link="${prefix}link_0" /> | |
<child link="${prefix}link_1" /> | |
<axis xyz="0.0 0.0 1.0" /> | |
<limit effort="${max_effort}" lower="${-170 * PI / 180}" upper="${170 * PI / 180}" | |
velocity="${max_velocity}" /> | |
<dynamics damping="${joint_damping}" friction="${joint_friction}" /> | |
</joint> | |
<joint name="${prefix}joint_a2" type="revolute"> | |
<origin rpy="0 0 0" xyz="-0.0 -0.0105 0.193" /> | |
<parent link="${prefix}link_1" /> | |
<child link="${prefix}link_2" /> | |
<axis xyz="0.0 1.0 0.0" /> | |
<limit effort="${max_effort}" lower="${-120 * PI / 180}" upper="${120 * PI / 180}" | |
velocity="${max_velocity}" /> | |
<dynamics damping="${joint_damping}" friction="${joint_friction}" /> | |
</joint> | |
<joint name="${prefix}joint_a3" type="revolute"> | |
<origin rpy="0 0 0" xyz="0.0 0.0105 0.1745" /> | |
<parent link="${prefix}link_2" /> | |
<child link="${prefix}link_3" /> | |
<axis xyz="0.0 0.0 1.0" /> | |
<limit effort="${max_effort}" lower="${-170 * PI / 180}" upper="${170 * PI / 180}" | |
velocity="${max_velocity}" /> | |
<dynamics damping="${joint_damping}" friction="${joint_friction}" /> | |
</joint> | |
<joint name="${prefix}joint_a4" type="revolute"> | |
<origin rpy="0 0 0" xyz="0.0 0.0105 0.2255" /> | |
<parent link="${prefix}link_3" /> | |
<child link="${prefix}link_4" /> | |
<axis xyz="0.0 -1.0 0.0" /> | |
<limit effort="${max_effort}" lower="${-120 * PI / 180}" upper="${120 * PI / 180}" | |
velocity="${max_velocity}" /> | |
<dynamics damping="${joint_damping}" friction="${joint_friction}" /> | |
</joint> | |
<joint name="${prefix}joint_a5" type="revolute"> | |
<origin rpy="0 0 0" xyz="0.0 -0.0105 0.1745" /> | |
<parent link="${prefix}link_4" /> | |
<child link="${prefix}link_5" /> | |
<axis xyz="0.0 0.0 1.0" /> | |
<limit effort="${max_effort}" lower="${-170 * PI / 180}" upper="${170 * PI / 180}" | |
velocity="${max_velocity}" /> | |
<dynamics damping="${joint_damping}" friction="${joint_friction}" /> | |
</joint> | |
<joint name="${prefix}joint_a6" type="revolute"> | |
<origin rpy="0 0 0" xyz="0.0 -0.0707 0.2255" /> | |
<parent link="${prefix}link_5" /> | |
<child link="${prefix}link_6" /> | |
<axis xyz="0.0 1.0 0.0" /> | |
<limit effort="${max_effort}" lower="${-120 * PI / 180}" upper="${120 * PI / 180}" | |
velocity="${max_velocity}" /> | |
<dynamics damping="${joint_damping}" friction="${joint_friction}" /> | |
</joint> | |
<joint name="${prefix}joint_a7" type="revolute"> | |
<origin rpy="0 0 0" xyz="0.0 0.0705 0.0909" /> | |
<parent link="${prefix}link_6" /> | |
<child link="${prefix}link_7" /> | |
<axis xyz="0.0 0.0 1.0" /> | |
<limit effort="${max_effort}" lower="${-175 * PI / 180}" upper="${175 * PI / 180}" | |
velocity="${max_velocity}" /> | |
<dynamics damping="${joint_damping}" friction="${joint_friction}" /> | |
</joint> | |
<joint name="${prefix}joint_a7-tool0" type="fixed"> | |
<parent link="${prefix}link_7" /> | |
<child link="${prefix}tool0" /> | |
<origin xyz="0 0 0.035" rpy="0 0 0" /> | |
<axis xyz="0 0 0" /> | |
</joint> | |
</xacro:macro> | |
</robot> |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment
Change name="iiwa" to "iiwa14"