Skip to content

Commit

Permalink
m10ia: update urdfs based on DH data. For ros-industrial#54 and ros-i…
Browse files Browse the repository at this point in the history
  • Loading branch information
gavanderhoorn committed Apr 13, 2014
1 parent b8af244 commit 6a710f5
Show file tree
Hide file tree
Showing 16 changed files with 19 additions and 19 deletions.
Binary file modified fanuc_m10ia_support/meshes/m10ia/collision/base_link.stl
Binary file not shown.
Binary file modified fanuc_m10ia_support/meshes/m10ia/collision/link_1.stl
Binary file not shown.
Binary file modified fanuc_m10ia_support/meshes/m10ia/collision/link_2.stl
Binary file not shown.
Binary file modified fanuc_m10ia_support/meshes/m10ia/collision/link_3.stl
Binary file not shown.
Binary file modified fanuc_m10ia_support/meshes/m10ia/collision/link_4.stl
Binary file not shown.
Binary file modified fanuc_m10ia_support/meshes/m10ia/collision/link_5.stl
Binary file not shown.
Binary file modified fanuc_m10ia_support/meshes/m10ia/collision/link_6.stl
Binary file not shown.
Binary file modified fanuc_m10ia_support/meshes/m10ia/visual/base_link.stl
Binary file not shown.
Binary file modified fanuc_m10ia_support/meshes/m10ia/visual/link_1.stl
Binary file not shown.
Binary file modified fanuc_m10ia_support/meshes/m10ia/visual/link_2.stl
Binary file not shown.
Binary file modified fanuc_m10ia_support/meshes/m10ia/visual/link_3.stl
Binary file not shown.
Binary file modified fanuc_m10ia_support/meshes/m10ia/visual/link_4.stl
Binary file not shown.
Binary file modified fanuc_m10ia_support/meshes/m10ia/visual/link_5.stl
Binary file not shown.
Binary file modified fanuc_m10ia_support/meshes/m10ia/visual/link_6.stl
Binary file not shown.
19 changes: 9 additions & 10 deletions fanuc_m10ia_support/urdf/m10ia.urdf
Expand Up @@ -6,7 +6,7 @@
<robot name="fanuc_m10ia" xmlns:xacro="http://ros.org/wiki/xacro">
<link name="base_link">
<visual>
<origin rpy="-1.578 0 0" xyz="0 0 0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://fanuc_m10ia_support/meshes/m10ia/visual/base_link.stl"/>
</geometry>
Expand All @@ -15,7 +15,7 @@
</material>
</visual>
<collision>
<origin rpy="-1.578 0 0" xyz="0 0 0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://fanuc_m10ia_support/meshes/m10ia/collision/base_link.stl"/>
</geometry>
Expand Down Expand Up @@ -125,51 +125,50 @@
</link>
<link name="tool0"/>
<joint name="joint_1" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="0 0 0" xyz="0 0 0.450"/>
<parent link="base_link"/>
<child link="link_1"/>
<axis xyz="0 0 1"/>
<limit effort="0" lower="-3.14" upper="3.14" velocity="3.67"/>
</joint>
<joint name="joint_2" type="revolute">
<origin rpy="0 0 0" xyz="0.15 -0.04 0.45"/>
<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="-1.57" upper="2.79" velocity="3.32"/>
</joint>
<joint name="joint_3" type="revolute">
<origin rpy="0 0 0" xyz="0 -0.0225 0.6"/>
<origin rpy="0 0 0" xyz="0 0 0.600"/>
<parent link="link_2"/>
<child link="link_3"/>
<axis xyz="0 -1 0"/>
<limit effort="0" lower="-3.14" upper="4.61" velocity="3.67"/>
</joint>
<joint name="joint_4" type="revolute">
<origin rpy="0 0 0" xyz="0.1805 0.0625 0.2"/>
<origin rpy="0 0 0" xyz="0 0 0.200"/>
<parent link="link_3"/>
<child link="link_4"/>
<axis xyz="-1 0 0"/>
<limit effort="0" lower="-3.31" upper="3.31" velocity="6.98"/>
</joint>
<joint name="joint_5" type="revolute">
<origin rpy="0 0 0" xyz="0.4595 -0.0565 0"/>
<origin rpy="0 0 0" xyz="0.640 0 0"/>
<parent link="link_4"/>
<child link="link_5"/>
<axis xyz="0 -1 0"/>
<limit effort="0" lower="-3.31" upper="3.31" velocity="6.98"/>
</joint>
<joint name="joint_6" type="revolute">
<origin rpy="0 0 0" xyz="0.1 0.0565 0"/>
<origin rpy="0 0 0" xyz="0.100 0 0"/>
<parent link="link_5"/>
<child link="link_6"/>
<axis xyz="-1 0 0"/>
<limit effort="0" lower="-6.28" upper="6.28" velocity="10.47"/>
</joint>
<joint name="joint_6-tool0" type="fixed">
<origin rpy="3.1415926535 -1.570796327 0" xyz="0 0 0"/>
<parent link="link_6"/>
<child link="tool0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
</robot>

19 changes: 10 additions & 9 deletions fanuc_m10ia_support/urdf/m10ia_macro.xacro
@@ -1,19 +1,20 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find fanuc_resources)/urdf/common_materials.xacro"/>
<xacro:include filename="$(find fanuc_resources)/urdf/common_constants.xacro"/>

<xacro:macro name="fanuc_m10ia" params="prefix">
<!-- links -->
<link name="${prefix}base_link">
<visual>
<origin xyz="0 0 0" rpy="-1.578 0 0"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://fanuc_m10ia_support/meshes/m10ia/visual/base_link.stl"/>
</geometry>
<xacro:material_fanuc_grey />
</visual>
<collision>
<origin xyz="0 0 0" rpy="-1.578 0 0"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://fanuc_m10ia_support/meshes/m10ia/collision/base_link.stl"/>
</geometry>
Expand Down Expand Up @@ -113,51 +114,51 @@

<!-- joints -->
<joint name="${prefix}joint_1" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0"/>
<origin xyz="0 0 0.450" rpy="0 0 0"/>
<parent link="${prefix}base_link"/>
<child link="${prefix}link_1"/>
<axis xyz="0 0 1"/>
<limit lower="-3.14" upper="3.14" effort="0" velocity="3.67"/>
</joint>
<joint name="${prefix}joint_2" type="revolute">
<origin xyz="0.15 -0.04 0.45" rpy="0 0 0"/>
<origin xyz="0.150 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_1"/>
<child link="${prefix}link_2"/>
<axis xyz="0 1 0"/>
<limit lower="-1.57" upper="2.79" effort="0" velocity="3.32"/>
</joint>
<joint name="${prefix}joint_3" type="revolute">
<origin xyz="0 -0.0225 0.6" rpy="0 0 0"/>
<origin xyz="0 0 0.600" rpy="0 0 0"/>
<parent link="${prefix}link_2"/>
<child link="${prefix}link_3"/>
<axis xyz="0 -1 0"/>
<limit lower="-3.14" upper="4.61" effort="0" velocity="3.67"/>
</joint>
<joint name="${prefix}joint_4" type="revolute">
<origin xyz="0.1805 0.0625 0.2" rpy="0 0 0"/>
<origin xyz="0 0 0.200" rpy="0 0 0"/>
<parent link="${prefix}link_3"/>
<child link="${prefix}link_4"/>
<axis xyz="-1 0 0"/>
<limit lower="-3.31" upper="3.31" effort="0" velocity="6.98"/>
</joint>
<joint name="${prefix}joint_5" type="revolute">
<origin xyz="0.4595 -0.0565 0" rpy="0 0 0"/>
<origin xyz="0.640 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_4"/>
<child link="${prefix}link_5"/>
<axis xyz="0 -1 0"/>
<limit lower="-3.31" upper="3.31" effort="0" velocity="6.98"/>
</joint>
<joint name="${prefix}joint_6" type="revolute">
<origin xyz="0.1 0.0565 0" rpy="0 0 0"/>
<origin xyz="0.100 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_5"/>
<child link="${prefix}link_6"/>
<axis xyz="-1 0 0"/>
<limit lower="-6.28" upper="6.28" effort="0" velocity="10.47"/>
</joint>
<joint name="${prefix}joint_6-tool0" type="fixed">
<origin xyz="0 0 0" rpy="${m_pi} ${-m_pi_2} 0" />
<parent link="${prefix}link_6"/>
<child link="${prefix}tool0"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
</joint>
</xacro:macro>
</robot>

0 comments on commit 6a710f5

Please sign in to comment.