-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathmodel-1_4.sdf
117 lines (112 loc) · 3.03 KB
/
model-1_4.sdf
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
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
<?xml version="1.0" ?>
<sdf version="1.4">
<model name="ball_valve">
<link name="handle">
<pose>0 0.0275 0.02222 -1.5708 3.1415 0</pose>
<inertial>
<mass>0.0802</mass>
<pose>0.0 0.0435 0.0055 0 0 0</pose>
<inertia>
<ixx>0.000038</ixx>
<iyy>0.000004</iyy>
<izz>0.00004</izz>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<mesh>
<uri>model://drc_practice_ball_valve/meshes/ball_valve.dae</uri>
</mesh>
</geometry>
<surface>
<bounce>
<restitution_coefficient>0.01</restitution_coefficient>
<threshold>5.0</threshold>
</bounce>
<friction>
<ode>
<mu>5</mu>
<mu2>5</mu2>
</ode>
</friction>
<contact>
<ode>
<soft_cfm>0.01</soft_cfm><!--"sponginess", 0.0=hard-->
<kp>10000.0</kp>
<kd>1000.0</kd>
<max_vel>0.01</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
</surface>
</collision>
<visual name="visual">
<geometry>
<mesh>
<uri>model://drc_practice_ball_valve/meshes/ball_valve.dae</uri>
</mesh>
</geometry>
</visual>
</link>
<!--
This is just a visual until SDF collide_bitmask is implemented.
Without collide_bitmask, the "attachment" will collide with a
wall that separates the handle from the attachment causing jitter
-->
<!--
<link name="attachment">
<pose>0 0 0.02222 0 0 0</pose>
<inertial>
<mass>0.802</mass>
<inertia>
<ixx>0.00017</ixx>
<iyy>0.00017</iyy>
<izz>0.00007</izz>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<mesh>
<uri>model://drc_practice_ball_valve/meshes/attachment.dae</uri>
</mesh>
</geometry>
</collision>
<visual name="visual">
<geometry>
<mesh>
<uri>model://drc_practice_ball_valve/meshes/attachment.dae</uri>
</mesh>
</geometry>
</visual>
</link>
-->
<joint name="ball" type="revolute">
<parent>world</parent>
<child>handle</child>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>0</lower>
<upper>1.58</upper>
</limit>
<dynamics>
<!--velocity dependent viscous damping coefficient of the joint-->
<damping>0.3</damping>
<!--default 0, static friction value of the joint-->
<friction>10</friction>
</dynamics>
</axis>
<physics>
<ode>
<cfm_damping>1</cfm_damping>
</ode>
</physics>
</joint>
</model>
</sdf>