Skip to content

Commit

Permalink
updated URDF. added tool0 frame as endeffector, with X point upwards
Browse files Browse the repository at this point in the history
  • Loading branch information
SalvoVirga committed Jan 7, 2016
1 parent 1a7e095 commit ae3ba27
Show file tree
Hide file tree
Showing 4 changed files with 56 additions and 26 deletions.
12 changes: 9 additions & 3 deletions iiwa_description/urdf/iiwa14.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -38,12 +38,11 @@
<!--Cuboid-->
<!--Cylinder: length is along the y-axis! -->
<!-- some constants -->
<!-- Flange lenghts -->
<!-- Fix to world just for testing -->
<link name="world"/>
<!--iiwa-->
<!--joint between {parent} and link_0-->
<joint name="world_joint" type="fixed">
<joint name="world_iiwa_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<parent link="world"/>
<child link="iiwa_link_0"/>
Expand Down Expand Up @@ -268,7 +267,7 @@
<origin rpy="-1.57079632679 3.14159265359 0" xyz="0 0.081 0"/>
<axis xyz="0 0 1"/>
<limit effort="300" lower="-3.05432619099" upper="3.05432619099" velocity="10"/>
<safety_controller k_position="100" k_velocity="2" soft_lower_limit="-2.05948851735" soft_upper_limit="2.05948851735"/>
<safety_controller k_position="100" k_velocity="2" soft_lower_limit="-3.01941960595" soft_upper_limit="3.01941960595"/>
<dynamics damping="0.5"/>
</joint>
<link name="iiwa_link_7">
Expand Down Expand Up @@ -300,6 +299,13 @@
</joint>
<link name="iiwa_link_ee">
</link>
<joint name="tool0_joint" type="fixed">
<parent link="iiwa_link_ee"/>
<child link="tool0"/>
<origin rpy="0 -1.57079632679 0" xyz="0 0 0"/>
</joint>
<link name="tool0">
</link>
<!--Extensions -->
<!-- Load Gazebo lib and set the robot namespace -->
<gazebo>
Expand Down
9 changes: 9 additions & 0 deletions iiwa_description/urdf/iiwa14.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -338,6 +338,15 @@

<link name="${robot_name}_link_ee">
</link>

<joint name="tool0_joint" type="fixed">
<parent link="${robot_name}_link_ee"/>
<child link="tool0"/>
<origin xyz="0 0 0" rpy="0 -${PI/2} 0"/>
</joint>

<link name="tool0">
</link>

<!--Extensions -->
<xacro:iiwa_gazebo robot_name="${robot_name}" />
Expand Down
50 changes: 28 additions & 22 deletions iiwa_description/urdf/iiwa7.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -38,12 +38,11 @@
<!--Cuboid-->
<!--Cylinder: length is along the y-axis! -->
<!-- some constants -->
<!-- Flange lenghts -->
<!-- Fix to world just for testing -->
<link name="world"/>
<!--iiwa-->
<!--joint between {parent} and link_0-->
<joint name="world_joint" type="fixed">
<joint name="world_iiwa_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.0"/>
<parent link="world"/>
<child link="iiwa_link_0"/>
Expand Down Expand Up @@ -79,7 +78,7 @@
<joint name="iiwa_joint_1" type="revolute">
<parent link="iiwa_link_0"/>
<child link="iiwa_link_1"/>
<origin rpy="0 0 0" xyz="0 0 0.1575"/>
<origin rpy="0 0 0" xyz="0 0 0.15"/>
<axis xyz="0 0 1"/>
<limit effort="300" lower="-2.96705972839" upper="2.96705972839" velocity="10"/>
<safety_controller k_position="100" k_velocity="2" soft_lower_limit="-2.93215314335" soft_upper_limit="2.93215314335"/>
Expand All @@ -92,14 +91,14 @@
<inertia ixx="0.1" ixy="0" ixz="0" iyy="0.09" iyz="0" izz="0.02"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="0 0 0" xyz="0 0 0.0075"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/iiwa7/visual/link_1.stl"/>
</geometry>
<material name="Orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="0 0 0" xyz="0 0 0.0075"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/iiwa7/collision/link_1.stl"/>
</geometry>
Expand All @@ -109,7 +108,7 @@
<joint name="iiwa_joint_2" type="revolute">
<parent link="iiwa_link_1"/>
<child link="iiwa_link_2"/>
<origin rpy="1.57079632679 0 3.14159265359" xyz="0 -0.0005 0.1840"/>
<origin rpy="1.57079632679 0 3.14159265359" xyz="0 0 0.19"/>
<axis xyz="0 0 1"/>
<limit effort="300" lower="-2.09439510239" upper="2.09439510239" velocity="10"/>
<safety_controller k_position="100" k_velocity="2" soft_lower_limit="-2.05948851735" soft_upper_limit="2.05948851735"/>
Expand All @@ -122,14 +121,14 @@
<inertia ixx="0.05" ixy="0" ixz="0" iyy="0.018" iyz="0" izz="0.044"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="0 0 0" xyz="0 0 -0.0060"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/iiwa7/visual/link_2.stl"/>
</geometry>
<material name="Orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="0 0 0" xyz="0 0 -0.0060"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/iiwa7/collision/link_2.stl"/>
</geometry>
Expand All @@ -139,7 +138,7 @@
<joint name="iiwa_joint_3" type="revolute">
<parent link="iiwa_link_2"/>
<child link="iiwa_link_3"/>
<origin rpy="1.57079632679 0 3.14159265359" xyz="0 0.184 0"/>
<origin rpy="1.57079632679 0 3.14159265359" xyz="0 0.21 0"/>
<axis xyz="0 0 1"/>
<limit effort="300" lower="-2.96705972839" upper="2.96705972839" velocity="10"/>
<safety_controller k_position="100" k_velocity="2" soft_lower_limit="-2.05948851735" soft_upper_limit="2.05948851735"/>
Expand All @@ -152,14 +151,14 @@
<inertia ixx="0.08" ixy="0" ixz="0" iyy="0.075" iyz="0" izz="0.01"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="0 0 0" xyz="0 -0.005 -0.026"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/iiwa7/visual/link_3.stl"/>
</geometry>
<material name="Orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="0 0 0" xyz="0 -0.005 -0.026"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/iiwa7/collision/link_3.stl"/>
</geometry>
Expand All @@ -169,7 +168,7 @@
<joint name="iiwa_joint_4" type="revolute">
<parent link="iiwa_link_3"/>
<child link="iiwa_link_4"/>
<origin rpy="1.57079632679 0 0" xyz="0 0 0.21550"/>
<origin rpy="1.57079632679 0 0" xyz="0 0 0.19"/>
<axis xyz="0 0 1"/>
<limit effort="300" lower="-2.09439510239" upper="2.09439510239" velocity="10"/>
<safety_controller k_position="100" k_velocity="2" soft_lower_limit="-2.05948851735" soft_upper_limit="2.05948851735"/>
Expand Down Expand Up @@ -199,10 +198,10 @@
<joint name="iiwa_joint_5" type="revolute">
<parent link="iiwa_link_4"/>
<child link="iiwa_link_5"/>
<origin rpy="-1.57079632679 3.14159265359 0" xyz="0 0.1840 0"/>
<origin rpy="-1.57079632679 3.14159265359 0" xyz="0 0.21 0"/>
<axis xyz="0 0 1"/>
<limit effort="300" lower="-2.96705972839" upper="2.96705972839" velocity="10"/>
<safety_controller k_position="100" k_velocity="2" soft_lower_limit="-2.05948851735" soft_upper_limit="2.05948851735"/>
<limit effort="300" lower="-3.05432619099" upper="3.05432619099" velocity="10"/>
<safety_controller k_position="100" k_velocity="2" soft_lower_limit="-3.01941960595" soft_upper_limit="3.01941960595"/>
<dynamics damping="0.5"/>
</joint>
<link name="iiwa_link_5">
Expand All @@ -212,14 +211,14 @@
<inertia ixx="0.02" ixy="0" ixz="0" iyy="0.018" iyz="0" izz="0.005"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="0 0 0" xyz="0 0 -0.026"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/iiwa7/visual/link_5.stl"/>
</geometry>
<material name="Orange"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="0 0 0" xyz="0 0 -0.026"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/iiwa7/collision/link_5.stl"/>
</geometry>
Expand All @@ -229,7 +228,7 @@
<joint name="iiwa_joint_6" type="revolute">
<parent link="iiwa_link_5"/>
<child link="iiwa_link_6"/>
<origin rpy="1.57079632679 0 0" xyz="0 0.06070 0.21550"/>
<origin rpy="1.57079632679 0 0" xyz="0 0.06070 0.19"/>
<axis xyz="0 0 1"/>
<limit effort="300" lower="-2.09439510239" upper="2.09439510239" velocity="10"/>
<safety_controller k_position="100" k_velocity="2" soft_lower_limit="-2.05948851735" soft_upper_limit="2.05948851735"/>
Expand Down Expand Up @@ -259,10 +258,10 @@
<joint name="iiwa_joint_7" type="revolute">
<parent link="iiwa_link_6"/>
<child link="iiwa_link_7"/>
<origin rpy="-1.57079632679 3.14159265359 0" xyz="0 0.0805 0.060"/>
<origin rpy="-1.57079632679 3.14159265359 0" xyz="0 0.081 0.06070"/>
<axis xyz="0 0 1"/>
<limit effort="300" lower="-3.05432619099" upper="3.05432619099" velocity="10"/>
<safety_controller k_position="100" k_velocity="2" soft_lower_limit="-2.05948851735" soft_upper_limit="2.05948851735"/>
<safety_controller k_position="100" k_velocity="2" soft_lower_limit="-3.01941960595" soft_upper_limit="3.01941960595"/>
<dynamics damping="0.5"/>
</joint>
<link name="iiwa_link_7">
Expand All @@ -272,14 +271,14 @@
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="0 0 0" xyz="0 0 -0.0005"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/iiwa7/visual/link_7_basic.stl"/>
</geometry>
<material name="Grey"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="0 0 0" xyz="0 0 -0.0005"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/iiwa7/collision/link_7_basic.stl"/>
</geometry>
Expand All @@ -294,6 +293,13 @@
</joint>
<link name="iiwa_link_ee">
</link>
<joint name="tool0_joint" type="fixed">
<parent link="iiwa_link_ee"/>
<child link="tool0"/>
<origin rpy="0 -1.57079632679 0" xyz="0 0 0"/>
</joint>
<link name="tool0">
</link>
<!--Extensions -->
<!-- Load Gazebo lib and set the robot namespace -->
<gazebo>
Expand Down
11 changes: 10 additions & 1 deletion iiwa_description/urdf/iiwa7.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -209,7 +209,7 @@

<joint name="${robot_name}_joint_5" type="revolute">
<parent link="${robot_name}_link_4"/>
<child link="${robot_name}_link_5"/>-169
<child link="${robot_name}_link_5"/>
<origin xyz="0 0.21 0" rpy="${-PI / 2} ${PI} 0"/>
<axis xyz="0 0 1"/>
<limit lower="${-175 * PI / 180}" upper="${175 * PI / 180}"
Expand Down Expand Up @@ -330,6 +330,15 @@
<link name="${robot_name}_link_ee">
</link>

<joint name="tool0_joint" type="fixed">
<parent link="${robot_name}_link_ee"/>
<child link="tool0"/>
<origin xyz="0 0 0" rpy="0 -${PI/2} 0"/>
</joint>

<link name="tool0">
</link>

<!--Extensions -->
<xacro:iiwa_gazebo robot_name="${robot_name}" />
<xacro:iiwa_transmission hardware_interface="${hardware_interface}"/>
Expand Down

0 comments on commit ae3ba27

Please sign in to comment.