Change description of Barrett Hand links.
authorWalter Fetter Lages <w.fetter@ieee.org>
Wed, 28 Nov 2018 22:27:39 +0000 (20:27 -0200)
committerWalter Fetter Lages <w.fetter@ieee.org>
Thu, 29 Nov 2018 19:09:46 +0000 (17:09 -0200)
ufrgs_bhand_description/xacro/bhand.urdf.xacro [new file with mode: 0644]
ufrgs_bhand_description/xacro/bhand0.urdf.xacro [new file with mode: 0644]
ufrgs_bhand_description/xacro/bhand_base.urdf.xacro [new file with mode: 0644]
ufrgs_bhand_description/xacro/bhand_link1.urdf.xacro [new file with mode: 0644]
ufrgs_bhand_description/xacro/bhand_link2.urdf.xacro [new file with mode: 0644]
ufrgs_bhand_description/xacro/bhand_link3.urdf.xacro [new file with mode: 0644]

diff --git a/ufrgs_bhand_description/xacro/bhand.urdf.xacro b/ufrgs_bhand_description/xacro/bhand.urdf.xacro
new file mode 100644 (file)
index 0000000..6194489
--- /dev/null
@@ -0,0 +1,70 @@
+<?xml version="1.0"?>
+<robot name="bhand" xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+  <xacro:property name="M_PI" value="3.1415926535897931" />
+  
+  <xacro:include filename="$(find ufrgs_bhand_description)/xacro/bhand_base.urdf.xacro" />
+  <xacro:include filename="$(find ufrgs_bhand_description)/xacro/bhand_link1.urdf.xacro" />
+  <xacro:include filename="$(find ufrgs_bhand_description)/xacro/bhand_link2.urdf.xacro" />
+  <xacro:include filename="$(find ufrgs_bhand_description)/xacro/bhand_link3.urdf.xacro" />
+
+  <link name="bhand_origin"/>
+
+  <xacro:bhand_base parent="origin" link="base_link" joint="base_joint"/>
+
+  <xacro:bhand_link1 parent="base_link" link="finger1_link_1" joint="spread" type="revolute">
+               <inertial_attr>
+                       <inertial>
+<!--
+       Inertia parameters from http://support.barrett.com/wiki/Hand/280/MassProperties
+
+       Finger spread frame
+-->
+                               <mass value="0.14109"/>
+                               <origin xyz="0.030616 -7.3219e-5 -0.011201"/>  
+                               <inertia ixx="2.0672e-5" ixy="2.6024e-7" ixz="6.3481e-6" iyy="7.4105e-5" iyz="1.7118e-8" izz="6.8207e-5"/>
+                       </inertial>
+               </inertial_attr>
+               <origin xyz="0.02475 0.0 ${0.1325-0.06}" rpy="0.0 0 ${M_PI}" /> 
+               <limit effort="30" velocity="1.5" lower="0.0" upper="${M_PI}" />
+               <mimic_attr/>
+  </xacro:bhand_link1>
+
+  <xacro:bhand_transmission joint="spread" />
+
+  <xacro:bhand_link1 parent="base_link" link="finger2_link_1" joint="spread_finger2" type="revolute">
+               <inertial_attr>
+                       <inertial>
+<!--
+       Inertia parameters from http://support.barrett.com/wiki/Hand/280/MassProperties
+
+       Finger spread frame
+-->
+                               <mass value="0.14109"/>
+                               <origin xyz="0.030616 -7.3219e-5 -0.011201"/>  
+                               <inertia ixx="2.0672e-5" ixy="2.6024e-7" ixz="6.3481e-6" iyy="7.4105e-5" iyz="1.7118e-8" izz="6.8207e-5"/>
+                       </inertial>
+               </inertial_attr>
+               <origin xyz="-0.02475 0.0 ${0.1325-0.06}" rpy="0.0 0 ${M_PI}" /> 
+               <limit effort="30" velocity="1.5" lower="-${M_PI}" upper="0.0" />
+               <mimic_attr>
+                       <mimic joint="bhand_spread" multiplier="-1.0" offset="0" />
+               </mimic_attr>
+  </xacro:bhand_link1>
+
+  <xacro:bhand_link1 parent="base_link" link="finger3_link_1" joint="finger3_joint_1" type="fixed">
+               <inertial_attr/>
+               <origin xyz="0.0 0.0 ${0.1325-0.06}" rpy="0.0 0 ${M_PI}" /> 
+               <limit effort="30" velocity="0.0" lower="0.0" upper="0.0" />
+               <mimic_attr/>
+  </xacro:bhand_link1>
+
+  <xacro:bhand_link2 parent="finger1_link_1" link="finger1_link_2" joint="finger1_joint_2" />
+  <xacro:bhand_link2 parent="finger2_link_1" link="finger2_link_2" joint="finger2_joint_2" />
+  <xacro:bhand_link2 parent="finger3_link_1" link="finger3_link_2" joint="finger3_joint_2" />
+
+  <xacro:bhand_link3 parent="finger1_link_2" link="finger1_link_3" joint="finger1_joint_3" mimic_joint="finger1_joint_2" />
+  <xacro:bhand_link3 parent="finger2_link_2" link="finger2_link_3" joint="finger2_joint_3" mimic_joint="finger2_joint_2" />
+  <xacro:bhand_link3 parent="finger3_link_2" link="finger3_link_3" joint="finger3_joint_3" mimic_joint="finger3_joint_2" />
+
+</robot>
diff --git a/ufrgs_bhand_description/xacro/bhand0.urdf.xacro b/ufrgs_bhand_description/xacro/bhand0.urdf.xacro
new file mode 100644 (file)
index 0000000..6344761
--- /dev/null
@@ -0,0 +1,14 @@
+<?xml version="1.0"?>
+<robot name="bhand" xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+       <link name="world" />
+
+       <include filename="$(find ufrgs_bhand_description)/xacro/bhand.urdf.xacro" />
+
+       <joint name="bhand_origin" type="fixed">
+               <parent link="world"/>
+               <child link="bhand_origin" />
+               <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
+       </joint>
+
+</robot>
diff --git a/ufrgs_bhand_description/xacro/bhand_base.urdf.xacro b/ufrgs_bhand_description/xacro/bhand_base.urdf.xacro
new file mode 100644 (file)
index 0000000..b1f3068
--- /dev/null
@@ -0,0 +1,55 @@
+<?xml version="1.0" ?>
+
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+   <xacro:property name="M_PI" value="3.1415926535897931" />
+   
+   <xacro:macro name="bhand_base" params="parent link joint">
+
+       <link name="bhand_${link}">
+               <inertial>
+<!--
+       Inertia parameters from http://support.barrett.com/wiki/Hand/280/MassProperties
+       
+       Hand base frame without palm pad.  Mass and inertia of finger 3 link
+       1 are included.
+-->
+                       <mass value="0.59573"/>
+                       <origin rpy="0 0 0" xyz="5.1098e-5 -0.0050433 0.036671" />  
+                       <inertia ixx="0.00067154" ixy="2.9365e-7" ixz="-7.6321e-7" iyy="0.00048844" iyz="-7.1984e-5" izz="0.00060401"/>
+               </inertial>
+               <visual>
+                       <origin rpy="0 0 ${-M_PI/2}" xyz="0 0 -0.06"/>
+                       <geometry>
+                               <mesh filename="package://ufrgs_bhand_description/meshes/bh_base.stl" />
+                       </geometry>
+                       <material name="Blue">
+                               <color rgba="0.0 0.0 0.5 1.0"/>
+                       </material>
+               </visual>
+               <collision>
+                       <origin rpy="0 0 ${-M_PI/2}" xyz="0 0 -0.06"/>
+                       <geometry>
+                               <mesh filename="package://ufrgs_bhand_description/meshes/bh_base.stl" />
+                       </geometry>
+                       <contact_coefficients kd="1.0" kp="1000.0" mu="0"/>
+               </collision>
+       </link>  
+
+       <gazebo reference="bhand_${link}">
+               <selfCollide>true</selfCollide>
+               <material>Gazebo/Blue</material>
+       </gazebo>
+
+
+       <joint name="bhand_${joint}" type="fixed">
+               <!--origin rpy="0 0 0" xyz="-0.060 -0.140 0.206"/-->
+               <!--origin rpy="0 0 0" xyz="0.22 0.14 0.346"/-->
+               <origin xyz="0.0 0.0 0.06" rpy="0.0 0.0 0.0" />
+               <child link="bhand_${link}"/>
+               <parent link="bhand_${parent}"/>
+       </joint>
+
+    </xacro:macro>
+
+</robot>
diff --git a/ufrgs_bhand_description/xacro/bhand_link1.urdf.xacro b/ufrgs_bhand_description/xacro/bhand_link1.urdf.xacro
new file mode 100644 (file)
index 0000000..cdf4d01
--- /dev/null
@@ -0,0 +1,79 @@
+<?xml version="1.0" ?>
+
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+  <xacro:macro name="bhand_link1" params="parent link joint type **inertial_attr *origin *limit **mimic_attr">
+
+       <link name="bhand_${link}">
+
+               <xacro:insert_block name="inertial_attr"/>
+               <inertial>
+<!--
+       Inertia parameters from http://support.barrett.com/wiki/Hand/280/MassProperties
+
+       Finger spread frame
+-->
+                       <mass value="0.14109"/>
+                       <origin xyz="0.030616 -7.3219e-5 -0.011201"/>  
+                       <inertia ixx="2.0672e-5" ixy="2.6024e-7" ixz="6.3481e-6" iyy="7.4105e-5" iyz="1.7118e-8" izz="6.8207e-5"/>
+               </inertial>
+               <visual>
+                       <origin rpy="0 0 ${M_PI/2}" xyz="0 0 0"/>
+                       <geometry>
+                               <mesh filename="package://ufrgs_bhand_description/meshes/bh_link1.stl" />
+                       </geometry>
+                       <material name="Grey">
+                               <color rgba="0.5 0.5 0.5 1.0"/>
+                       </material>
+               </visual>
+               <collision>
+                       <origin rpy="0 0 ${M_PI/2}" xyz="0 0 0"/>
+                       <geometry>
+                               <mesh filename="package://ufrgs_bhand_description/meshes/bh_link1.stl" />
+                       </geometry>
+                       <contact_coefficients kd="1.0" kp="1000.0" mu="0"/>
+               </collision>
+       </link>  
+
+       <gazebo reference="bhand_${link}">
+               <material>Gazebo/Grey</material>
+               <selfCollide>true</selfCollide>
+       </gazebo> 
+
+       <joint name="bhand_${joint}" type="${type}">
+               <!--origin xyz="-0.02475 0.0 0.0395" rpy="0.0 0 1.57079633" /--> 
+               <!--origin xyz="0.0 0.02475 0.1325" rpy="0.0 0 0" /--> 
+
+               <xacro:insert_block name="origin" />
+
+               <parent link="bhand_${parent}"/>
+               <child link="bhand_${link}" />
+               <axis xyz="0 0 1"/>
+
+               <xacro:insert_block name="limit" />
+
+               <!--joint_properties damping="100.0" friction="1000.0" /-->
+               <dynamics damping="1000"/>
+
+               <xacro:insert_block name="mimic_attr"/>
+
+       </joint >
+
+  </xacro:macro>
+
+  <xacro:macro name="bhand_transmission" params="joint">
+
+       <transmission name="bhand_${joint}_transmission">
+               <type>transmission_interface/SimpleTransmission</type>
+               <joint name="bhand_${joint}">
+                       <hardwareInterface>PositionJointInterface</hardwareInterface>
+               </joint>
+               <actuator name="bhand_${joint}_actuator">
+                       <hardwareInterface>PositionJointInterface</hardwareInterface>
+                       <mechanicalReduction>1</mechanicalReduction>
+               </actuator>
+       </transmission>
+
+  </xacro:macro>
+
+</robot>
diff --git a/ufrgs_bhand_description/xacro/bhand_link2.urdf.xacro b/ufrgs_bhand_description/xacro/bhand_link2.urdf.xacro
new file mode 100644 (file)
index 0000000..0a7bd35
--- /dev/null
@@ -0,0 +1,69 @@
+<?xml version="1.0" ?>
+
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+  <xacro:macro name="bhand_link2" params="parent link joint">
+
+       <link name="bhand_${link}">
+               <inertial>
+<!--
+       Inertia parameters from http://support.barrett.com/wiki/Hand/280/MassProperties
+
+       Finger inner link frame with fingertip torque sensor
+-->
+                       <mass value="0.062139"/>
+                       <origin xyz="0.023133 0.00078642 0.00052792"/>  
+                       <inertia ixx="4.8162e-6" ixy="5.7981e-7" ixz="-7.2483e-7" iyy="4.3317e-5" iyz="-2.6653e-9" izz="4.4441e-5"/>
+               </inertial>
+               <visual>
+                       <origin rpy="0 0 0" xyz="0 0 0"/>
+                       <geometry>
+                               <mesh filename="package://ufrgs_bhand_description/meshes/bh_link2.stl" />
+                       </geometry>
+                       <material name="Grey">
+                               <color rgba="0.5 0.5 0.5 1.0"/>
+                       </material>
+               </visual>
+               <collision>
+                       <origin rpy="0 0 0" xyz="0 0 0"/>
+                       <geometry>
+                               <mesh filename="package://ufrgs_bhand_description/meshes/bh_link2.stl" />
+                       </geometry>
+                       <contact_coefficients kd="1.0" kp="1000.0" mu="0"/>
+               </collision>
+       </link>  
+
+       <gazebo reference="bhand_${link}">
+               <material>Gazebo/Grey</material>
+               <selfCollide>true</selfCollide>
+       </gazebo> 
+
+       <joint name="bhand_${joint}" type="revolute">
+               <!--origin xyz="-0.02475 0.0 0.0395" rpy="0.0 0 1.57079633" /--> 
+               <!--origin xyz="0.0 0.02475 0.1325" rpy="0.0 0 0" /--> 
+
+               <origin xyz="0.0 0.05 0.0" rpy="${M_PI/2} 0.0 ${M_PI/2}" />
+               <parent link="bhand_${parent}"/>
+               <child link="bhand_${link}" />
+               <axis xyz="0 0 1"/>
+               <limit effort="30" velocity="1.5" lower="0.0" upper="${140 * M_PI / 180}" />
+
+               <!--joint_properties damping="100.0" friction="1000.0" /-->
+               <dynamics damping="1000"/>
+
+       </joint >
+
+       <transmission name="bhand_${joint}_transmission">
+               <type>transmission_interface/SimpleTransmission</type>
+               <joint name="bhand_${joint}">
+                       <hardwareInterface>PositionJointInterface</hardwareInterface>
+               </joint>
+               <actuator name="bhand_${joint}_actuator">
+                       <hardwareInterface>PositionJointInterface</hardwareInterface>
+                       <mechanicalReduction>1</mechanicalReduction>
+               </actuator>
+       </transmission>
+
+  </xacro:macro>
+
+</robot>
diff --git a/ufrgs_bhand_description/xacro/bhand_link3.urdf.xacro b/ufrgs_bhand_description/xacro/bhand_link3.urdf.xacro
new file mode 100644 (file)
index 0000000..581241a
--- /dev/null
@@ -0,0 +1,78 @@
+<?xml version="1.0" ?>
+
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+  <xacro:macro name="bhand_link3" params="parent link joint mimic_joint">
+
+       <link name="bhand_${link}">
+               <inertial>
+<!--
+       Inertia parameters from http://support.barrett.com/wiki/Hand/280/MassProperties
+
+       Fingertip frame without fingertip pressure pad
+-->
+                       <mass value="0.041377"/>
+                       <origin xyz="0.022825 0.0010491 0.00042038"/>  
+                       <inertia ixx="3.1053e-6" ixy="4.3996e-7" ixz="-2.9595e-7" iyy="1.6812e-5" iyz="-1.8205e-8" izz="1.5673e-5"/>
+               </inertial>
+               <visual>
+                       <origin rpy="0 0 0" xyz="0 0 0"/>
+                       <geometry>
+                               <mesh filename="package://ufrgs_bhand_description/meshes/bh_link3.stl" />
+                       </geometry>
+                       <material name="Grey">
+                               <color rgba="0.5 0.5 0.5 1.0"/>
+                       </material>
+               </visual>
+               <collision>
+                       <origin rpy="0 0 0" xyz="0 0 0"/>
+                       <geometry>
+                               <mesh filename="package://ufrgs_bhand_description/meshes/bh_link3.stl" />
+                       </geometry>
+                       <contact_coefficients kd="1.0" kp="1000.0" mu="0"/>
+               </collision>
+       </link>  
+
+       <gazebo reference="bhand_${link}">
+               <material>Gazebo/Grey</material>
+               <selfCollide>true</selfCollide>
+       </gazebo> 
+
+       <joint name="bhand_${joint}" type="revolute">
+               <!--origin xyz="-0.02475 0.0 0.0395" rpy="0.0 0 1.57079633" /--> 
+               <!--origin xyz="0.0 0.02475 0.1325" rpy="0.0 0 0" /--> 
+               <!--origin xyz="0.070 0 0" rpy="0 0 ${42 * M_PI / 180}" /-->
+
+               <origin xyz="0.070 0.0 0.0" rpy="0.0 0 0.0" /> 
+               <parent link="bhand_${parent}"/>
+               <child link="bhand_${link}" />
+               <axis xyz="0 0 1"/>
+               
+               <!--limit lower="0" upper="${48 * M_PI / 180}" effort="30" velocity="2.0"/-->
+               <limit effort="30" velocity="1.5" lower="${40 * M_PI / 180}" upper="2.44346095" />
+
+               <!--joint_properties damping="100.0" friction="1000.0" /-->
+               <dynamics damping="1000"/>
+
+               <mimic joint="bhand_${mimic_joint}" multiplier="${48 / 140}" offset="${40 * M_PI / 180}"/>
+
+       </joint >
+
+  </xacro:macro>
+
+  <xacro:macro name="bhand_transmission" params="joint">
+
+       <transmission name="bhand_${joint}_transmission">
+               <type>transmission_interface/SimpleTransmission</type>
+               <joint name="bhand_${joint}">
+                       <hardwareInterface>PositionJointInterface</hardwareInterface>
+               </joint>
+               <actuator name="bhand_${joint}_actuator">
+                       <hardwareInterface>PositionJointInterface</hardwareInterface>
+                       <mechanicalReduction>1</mechanicalReduction>
+               </actuator>
+       </transmission>
+
+  </xacro:macro>
+
+</robot>