Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

F hand lite urdf #185

Merged
merged 10 commits into from
Jan 6, 2015
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
294 changes: 294 additions & 0 deletions sr_description/hand/model/forearm_lite.dae

Large diffs are not rendered by default.

48 changes: 48 additions & 0 deletions sr_description/hand/xacro/forearm/forearm_lite.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<!-- muscle is true for muscle hand or false for motor hand -->
<!-- prefix can be anything but usually is "r_" or "l_" for right and left hands distinction -->
<xacro:macro name="forearm" params="muscle prefix">
<property name="M_PI" value="3.1415926535897931" />

<link name="${prefix}forearm">
<inertial>
<origin xyz="0 0 0.09" rpy="0 0 0"/>
<!-- TODO: This is a rough estimate. Total hand is 2359g -->
<mass value="1.8" />
<inertia ixx="0.108" ixy="0.0" ixz="0.0" iyy="0.108" iyz="0.0" izz="0.054" />
</inertial>

<visual>
<origin xyz="0 0 0" rpy="0 0 ${M_PI/2}" />
<geometry name="${prefix}forearm_visual">
<xacro:if value="${muscle}">
<mesh filename="package://sr_description/hand/model/forearm_lite.dae"
scale="1.0 1.0 1.0"/>
</xacro:if>
<xacro:unless value="${muscle}">
<mesh filename="package://sr_description/hand/model/forearm_lite.dae"
scale="1.0 1.0 1.0"/>
</xacro:unless>
</geometry>
<material name="Grey" />
</visual>

<collision>
<xacro:if value="${muscle}">
<origin xyz="0 0 0.185" rpy="0 0 0" />
<geometry name="${prefix}forearm_collision">
<cylinder radius="0.075" length="0.37"/>
</geometry>
</xacro:if>
<xacro:unless value="${muscle}">
<origin xyz="0 0 0.0775" rpy="0 0 0" />
<geometry name="${prefix}forearm_collision">
<box size="0.109 0.120 0.155" />
</geometry>
</xacro:unless>
</collision>
</link>

</xacro:macro>

</robot>
69 changes: 69 additions & 0 deletions sr_description/hand/xacro/hand_lite.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
<robot xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:include filename="$(find sr_description)/hand/xacro/forearm/forearm_lite.urdf.xacro" />
<xacro:include filename="$(find sr_description)/hand/xacro/wrist/wrist.urdf.xacro" />
<xacro:include filename="$(find sr_description)/hand/xacro/palm/palm_lite.urdf.xacro" />
<xacro:include filename="$(find sr_description)/hand/xacro/finger/fingers.urdf.xacro" />
<xacro:include filename="$(find sr_description)/hand/xacro/thumb/thumb.urdf.xacro" />

<property name="M_PI" value="3.1415926535897931" />

<!-- muscletrans is true for muscle transmission to be used, false to use motor transmission -->
<!-- muscle is true for muscle hand or false for motor hand -->
<!-- bio is true for biotac finger or false for standard finger -->
<!-- ubi is true for ubi finger or false for standard finger -->
<!-- eli is true for ellipsoid fingertip or false for standard finger -->
<!-- reflect is either 1 (for right hand) or -1 (for left hand) -->
<!-- prefix can be anything but usually is "r_" or "l_" for right and left hands distinction -->
<xacro:macro name="shadowhand" params="muscletrans muscle bio ubi eli reflect prefix">
<!-- Forearm -->
<xacro:forearm muscle="${muscle}" prefix="${prefix}" />

<!-- Wrist -->
<!-- Completely fixed on the lite hand. Bent back at 40 degrees -->
<!--
<xacro:wrist muscletrans="false" prefix="${prefix}" reflect="${reflect}" parent="${prefix}forearm">
<origin xyz="0 -0.010 0.213" rpy="0 0 0" />
</xacro:wrist>
-->
<joint name="${prefix}WRJ1" type="fixed">
<parent link="${prefix}forearm"/>
<child link="${prefix}palm"/>
<!-- <origin xyz="0 -0.010 0.213" rpy="-${M_PI/4} 0 0" /> -->
<origin xyz="0 -0.015 0.149" rpy="-${40*M_PI/180} 0 0" />
<axis xyz="0 ${reflect} 0" />
</joint>

<!-- Palm -->
<xacro:palm muscletrans="${muscletrans}" prefix="${prefix}" reflect="${reflect}" parent="${prefix}wrist" />

<!-- First Finger -->
<xacro:finger muscletrans="${muscletrans}" lf="false" bio="${bio}" ubi="${ubi}" eli="${eli}" prefix="${prefix}" reflect="${reflect}" link_prefix="ff" joint_prefix="FF" parent="${prefix}palm">
<origin xyz="${reflect*0.033} 0 0.095" rpy="0 0 0" />
<axis xyz="0 ${-1*reflect} 0" />
</xacro:finger>

<!-- Middle Finger -->
<xacro:finger muscletrans="${muscletrans}" lf="false" bio="${bio}" ubi="${ubi}" eli="${eli}" prefix="${prefix}" reflect="${reflect}" link_prefix="mf" joint_prefix="MF" parent="${prefix}palm">
<origin xyz="${reflect*0.011} 0 0.099" rpy="0 0 0" />
<axis xyz="0 ${-1*reflect} 0" />
</xacro:finger>

<!-- Ring Finger -->
<xacro:finger muscletrans="${muscletrans}" lf="false" bio="${bio}" ubi="${ubi}" eli="${eli}" prefix="${prefix}" reflect="${reflect}" link_prefix="rf" joint_prefix="RF" parent="${prefix}palm">
<origin xyz="${reflect*-0.011} 0 0.095" rpy="0 0 0" />
<axis xyz="0 ${reflect} 0" />
</xacro:finger>

<!-- No Little Finger on Lite hand -->

<!-- Thumb -->
<xacro:thumb muscletrans="${muscletrans}" bio="${bio}" ubi="${ubi}" eli="${eli}" prefix="${prefix}" reflect="${reflect}" is_lite="1" parent="${prefix}palm">
</xacro:thumb>

</xacro:macro>

</robot>
2 changes: 1 addition & 1 deletion sr_description/hand/xacro/palm/palm.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@
effort="30" velocity="1.0"/>
<dynamics damping="0.1"/>
</joint>

<!-- extensions -->
<xacro:shadowhand_palm_transmission muscletrans="${muscletrans}" prefix="${prefix}" />
<xacro:shadowhand_palm_gazebo prefix="${prefix}" />
Expand Down
89 changes: 89 additions & 0 deletions sr_description/hand/xacro/palm/palm_lite.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,89 @@
<robot xmlns:xacro="http://ros.org/wiki/xacro"
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#slider"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body"
xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom">

<xacro:include filename="$(find sr_description)/hand/xacro/palm/palm.gazebo.xacro" />
<xacro:include filename="$(find sr_description)/hand/xacro/palm/palm.transmission.xacro" />

<!-- muscletrans is true for muscle transmission or false for motor transmission -->
<!-- prefix can be anything but usually is "r_" or "l_" for right and left hands distinction -->
<!-- reflect is either 1 (for right hand) or -1 (for left hand) -->
<!-- parent is the parent link for the joint -->
<xacro:macro name="palm" params="muscletrans prefix reflect parent">
<link name="${prefix}palm">
<inertial>
<origin xyz="0 0 0.035" rpy="0 0 0" />
<mass value="0.3" />
<inertia ixx="0.003581" ixy="0.0" ixz="0.0" iyy="0.005287" iyz="0.0" izz="0.002545" />
</inertial>

<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry name="${prefix}palm_visual">
<mesh filename="package://sr_description/hand/model/palm.dae"
scale="${reflect*0.001} 0.001 0.001" />
</geometry>
<material name="Grey"/>
</visual>

<collision>
<origin xyz="${reflect*0.011} 0.0085 0.038" rpy="0 0 0" />
<geometry name="${prefix}palm_collision_geom">
<box size="0.062 0.007 0.098" />
</geometry>
</collision>
<collision>
<origin xyz="${reflect*0.0005} -0.0035 0.038" rpy="0 0 0" />
<geometry>
<box size="0.041 0.017 0.098" />
</geometry>
</collision>
<!-- palm complement below first finger -->
<collision>
<origin xyz="${reflect*0.0315} -0.0035 0.073" rpy="0 0 0" />
<geometry>
<box size="0.021 0.017 0.028" />
</geometry>
</collision>
<!-- thumb pulp side -->
<collision>
<origin xyz="${reflect*0.0315} -0.0085 0.001" rpy="0 0 0" />
<geometry>
<box size="0.021 0.027 0.024" />
</geometry>
</collision>
<!-- thumb pulp central -->
<collision>
<origin xyz="${reflect*0.01} -0.017 0.011" rpy="0 0 0" />
<geometry>
<box size="0.022 0.010 0.044" />
</geometry>
</collision>
<!-- above middle finger-->
<collision>
<origin xyz="${reflect*0.011} 0 0.089" rpy="0 0 0" />
<geometry>
<box size="0.018 0.024 0.004" />
</geometry>
</collision>
<!-- metacarpal side-->
<collision>
<origin xyz="${reflect*-0.030} 0 0.009" rpy="0 0 0" />
<geometry>
<box size="0.020 0.024 0.040" />
</geometry>
</collision>
</link>

<!-- No wrist joints in a Lite palm -->

<!-- extensions -->
<xacro:shadowhand_palm_transmission muscletrans="${muscletrans}" prefix="${prefix}" />
<xacro:shadowhand_palm_gazebo prefix="${prefix}" />
</xacro:macro>

</robot>
31 changes: 21 additions & 10 deletions sr_description/hand/xacro/thumb/thhub.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,8 @@
<!-- reflect is either 1 (for right hand) or -1 (for left hand) -->
<!-- prefix can be anything but usually is "r_" or "l_" for right and left hands distinction -->
<!-- parent is the parent link for the first joint -->
<xacro:macro name="thhub" params="muscle prefix parent">
<!-- is_lite is this the lite hand, if so lock J3 -->
<xacro:macro name="thhub" params="muscle prefix parent is_lite">
<link name="${prefix}thhub">
<inertial>
<mass value="0.01" />
Expand All @@ -38,15 +39,25 @@
</collision>
</link>

<joint name="${prefix}THJ3" type="revolute">
<parent link="${parent}"/>
<child link="${prefix}thhub"/>
<origin xyz="0 0 0.038" rpy="0 0 0" />
<axis xyz="1 0 0" />
<limit lower="${-12/180*M_PI}" upper="${12/180*M_PI}" effort="10"
velocity="1.0" />
<dynamics damping="0.1"/>
</joint>
<xacro:if value="${is_lite}">
<joint name="${prefix}THJ3" type="fixed">
<parent link="${parent}"/>
<child link="${prefix}thhub"/>
<origin xyz="0 0 0.038" rpy="0 0 0" />
<axis xyz="1 0 0" />
</joint>
</xacro:if>
<xacro:unless value="${is_lite}">
<joint name="${prefix}THJ3" type="revolute">
<parent link="${parent}"/>
<child link="${prefix}thhub"/>
<origin xyz="0 0 0.038" rpy="0 0 0" />
<axis xyz="1 0 0" />
<limit lower="${-12/180*M_PI}" upper="${12/180*M_PI}" effort="10"
velocity="1.0" />
<dynamics damping="0.1"/>
</joint>
</xacro:unless>

<!-- extensions -->
<xacro:thhub_transmission muscletrans="${muscle}" prefix="${prefix}"/>
Expand Down
5 changes: 3 additions & 2 deletions sr_description/hand/xacro/thumb/thumb.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -12,15 +12,16 @@
<!-- reflect is either 1 (for right hand) or -1 (for left hand) -->
<!-- prefix can be anything but usually is "r_" or "l_" for right and left hands distinction -->
<!-- parent is the parent link for the first joint -->
<xacro:macro name="thumb" params="muscletrans bio ubi eli reflect prefix parent">
<!-- is_lite is this the lite hand, if so lock J3 -->
<xacro:macro name="thumb" params="muscletrans bio ubi eli reflect prefix parent is_lite">
<!-- Base -->
<xacro:thbase muscle="${muscletrans}" prefix="${prefix}" reflect="${reflect}" parent="${parent}">
</xacro:thbase>
<!-- Proximal -->
<xacro:thproximal muscle="${muscletrans}" prefix="${prefix}" reflect="${reflect}" parent="${prefix}thbase">
</xacro:thproximal>
<!-- Hub -->
<xacro:thhub muscle="${muscletrans}" prefix="${prefix}" parent="${prefix}thproximal">
<xacro:thhub muscle="${muscletrans}" prefix="${prefix}" parent="${prefix}thproximal" is_lite="${is_lite}">>
</xacro:thhub>
<!-- Middle -->
<xacro:thmiddle muscle="${muscletrans}" bio="${bio}" prefix="${prefix}" parent="${prefix}thhub">
Expand Down
14 changes: 14 additions & 0 deletions sr_description/robots/shadowhand_lite.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
<robot xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:xacro="http://www.ros.org/wiki/xacro"
name="shadowhand_motor">

<xacro:include filename="$(find sr_description)/materials.urdf.xacro" />
<xacro:include filename="$(find sr_description)/hand/xacro/hand_lite.urdf.xacro" />
<xacro:include filename="$(find sr_description)/other/xacro/gazebo/gazebo.urdf.xacro" />

<xacro:shadowhand muscletrans="false" muscle="false" bio="false" ubi="false" eli="false" reflect="1.0" prefix="" />


</robot>