1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
|
<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">
<include filename="$(find sr_hand)/model/hand_urdf/thumb/thdistal.transmission.xacro" />
<xacro:macro name="thdistal" params="parent">
<link name="thdistal">
<inertial>
<mass value="0.016" />
<origin xyz="0 0 0.01375" rpy="0 0 0"/>
<inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0"
izz="0.1" />
</inertial>
<visual>
<origin xyz="0 0.002 0.0025" rpy="0 0 0" />
<geometry name="thdistal_visual">
<mesh filename="package://sr_hand/model/meshes/distal_ellipsoid.dae" scale="0.001 0.001 0.001" />
</geometry>
<material name="shadow_thmiddle_material">
<color rgba="0.2 0.2 0.2 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0.002 0.0025" rpy="0 0 0 " />
<geometry name="thmiddle_collision_geom">
<mesh filename="package://sr_hand/model/meshes/distal_ellipsoid.dae" scale="0.001 0.001 0.001" />
</geometry>
</collision>
</link>
<gazebo reference="thdistal">
<sensor:contact name="thdistal_contact_sensor">
<geom>thdistal_geom</geom>
<updateRate>100.0</updateRate>
<controller:gazebo_ros_bumper name="thdistal_gazebo_ros_bumper_controller" plugin="libgazebo_ros_bumper.so">
<alwaysOn>true</alwaysOn>
<updateRate>100.0</updateRate>
<frameName>thdistal</frameName>
<bumperTopicName>thdistal_bumper</bumperTopicName>
<interface:bumper name="thdistal_gazebo_ros_bumper_iface" />
</controller:gazebo_ros_bumper>
</sensor:contact>
<mu1 value="500.0" />
<mu2 value="500.0" />
<kp value="10000000.0" />
<kd value="1.0" />
<material>Gazebo/Grey</material>
<selfCollide>false</selfCollide>
</gazebo>
<joint name="THJ1" type="revolute">
<parent link="${parent}"/>
<child link="thdistal"/>
<origin xyz="0 0 0.032" rpy="0 0 -1.570796327" />
<axis xyz="1 0 0" />
<limit lower="0" upper="1.571" effort="10"
velocity="1.0" />
<dynamics damping="50.5"/>
</joint>
<link name="thtip">
<inertial>
<mass value="0.001" />
<inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0" />
</inertial>
</link>
<joint name="thtip" type="fixed">
<parent link="thdistal"/>
<child link="thtip"/>
<origin xyz="0 0 0.0275" rpy="0 0 0" />
</joint>
<xacro:thdistal_transmission />
</xacro:macro>
</robot>
|