1
<robot xmlns:xacro="http://ros.org/wiki/xacro"
2
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
3
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
4
xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#slider"
5
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
6
xmlns:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body"
7
xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom">
9
<include filename="$(find sr_hand)/model/hand_urdf/thumb/thmiddle.transmission.xacro" />
11
<xacro:macro name="thmiddle" params="parent">
13
<link name="thmiddle">
15
<mass value="0.016" />
16
<origin xyz="0 0 0" rpy="0 0 0"/>
17
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0"
21
<origin xyz="0 0 0" rpy="0 0 0" />
22
<geometry name="thmiddle_visual">
23
<mesh filename="package://sr_hand/model/meshes/TH2_z.mesh" scale="0.001 0.001 0.001" />
25
<material name="shadow_thmiddle_material">
26
<color rgba="0.2 0.2 0.2 1.0"/>
30
<origin xyz="0 0 0.025" rpy="0 0 0 " />
31
<geometry name="thmiddle_collision_geom">
32
<box size="0.005 0.005 0.015" />
36
<gazebo reference="thmiddle">
37
<sensor:contact name="thmiddle_contact_sensor">
38
<geom>thmiddle_geom</geom>
39
<updateRate>100.0</updateRate>
40
<controller:gazebo_ros_bumper name="thmiddle_gazebo_ros_bumper_controller" plugin="libgazebo_ros_bumper.so">
41
<alwaysOn>true</alwaysOn>
42
<updateRate>100.0</updateRate>
43
<frameName>thmiddle</frameName>
44
<bumperTopicName>thmiddle_bumper</bumperTopicName>
45
<interface:bumper name="thmiddle_gazebo_ros_bumper_iface" />
46
</controller:gazebo_ros_bumper>
48
<material>Gazebo/Grey</material>
51
<joint name="THJ2" type="revolute">
52
<parent link="${parent}"/>
53
<child link="thmiddle"/>
54
<origin xyz="0 0 0" rpy="0 0 0" />
56
<limit lower="-0.5237" upper="0.5237" effort="10"
58
<dynamics damping="50.5"/>
61
<xacro:thmiddle_transmission />