This repository was archived by the owner on Feb 3, 2025. It is now read-only.
-
Notifications
You must be signed in to change notification settings - Fork 497
/
Copy pathforce_torque_test.world
173 lines (169 loc) · 5.21 KB
/
force_torque_test.world
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
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
<?xml version="1.0" ?>
<sdf version="1.4">
<world name="default">
<physics type="ode">
<gravity>0.000000 0.000000 -9.810000</gravity>
<ode>
<solver>
<type>quick</type>
<iters>1000</iters>
<precon_iters>0</precon_iters>
<sor>1.000000</sor>
</solver>
<constraints>
<cfm>0.000000</cfm>
<erp>0.200000</erp>
<contact_max_correcting_vel>100.000000</contact_max_correcting_vel>
<contact_surface_layer>0.01000</contact_surface_layer>
</constraints>
</ode>
<bullet>
<solver>
<type>sequential_impulse</type>
<iters>1000</iters>
<sor>1.000000</sor>
</solver>
<constraints>
<cfm>0.000000</cfm>
<erp>0.200000</erp>
<split_impulse>true</split_impulse>
<split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>
<contact_surface_layer>0.00000</contact_surface_layer>
</constraints>
</bullet>
<real_time_update_rate>0.000000</real_time_update_rate>
<max_step_size>0.001</max_step_size>
</physics>
<include>
<uri>model://ground_plane</uri>
</include>
<include>
<uri>model://sun</uri>
</include>
<!-- to demonstrate force torque, we'll construct a model with
two bodies stacked vertically, with a x-revolute joint connecting
them. The joint has 90 degree limit. We'll test force
torque readings and characterize them. -->
<model name="model_1">
<link name="link_1">
<inertial>
<pose>0 0 0.5 0 0 0</pose>
<inertia>
<ixx>0.100000</ixx>
<ixy>0.000000</ixy>
<ixz>0.000000</ixz>
<iyy>0.100000</iyy>
<iyz>0.000000</iyz>
<izz>0.100000</izz>
</inertia>
<mass>10.000000</mass>
</inertial>
<visual name="visual_sphere">
<pose>0 0 0.5 0 0 0</pose>
<geometry>
<sphere>
<radius>0.100000</radius>
</sphere>
</geometry>
</visual>
<collision name="collision_sphere">
<pose>0 0 0.5 0 0 0</pose>
<max_contacts>250</max_contacts>
<geometry>
<sphere>
<radius>0.100000</radius>
</sphere>
</geometry>
</collision>
</link>
<link name="link_2">
<pose>0 0 1.5 0 0 0</pose>
<inertial>
<pose>0 0 0.5 0 0 0</pose>
<inertia>
<ixx>0.100000</ixx>
<ixy>0.000000</ixy>
<ixz>0.000000</ixz>
<iyy>0.100000</iyy>
<iyz>0.000000</iyz>
<izz>0.100000</izz>
</inertia>
<mass>10.000000</mass>
</inertial>
<visual name="visual_box">
<pose>0 0 0.5 0 0 0</pose>
<geometry>
<box>
<size>0.1 0.2 0.4</size>
</box>
</geometry>
</visual>
<collision name="collision_box">
<pose>0 0 0.5 0 0 0</pose>
<geometry>
<box>
<size>0.1 0.2 0.4</size>
</box>
</geometry>
</collision>
</link>
<joint name="joint_01" type="revolute">
<parent>world</parent>
<child>link_1</child>
<!-- joint at origin of link_1 inertial frame -->
<!-- moement arm from link_1 inertial frame to joint_01 is 0m -->
<pose>0 0 0.5 0 0 0</pose>
<axis>
<limit>
<lower>-1.57079</lower>
<upper>1.57079</upper>
<effort>1000.000000</effort>
<velocity>1000.000000</velocity>
</limit>
<dynamics>
<damping>0.000000</damping>
<friction>0.000000</friction>
</dynamics>
<xyz>1.000000 0.000000 0.000000</xyz>
</axis>
<sensor name="force_torque" type="force_torque">
<always_on>true</always_on>
<visualize>true</visualize>
<update_rate>30</update_rate>
</sensor>
<physics>
<provide_feedback>true</provide_feedback>
</physics>
</joint>
<joint name="joint_12" type="revolute">
<parent>link_1</parent>
<child>link_2</child>
<!-- joint_1 at origin of link_2 link frame -->
<!-- moement arm from link_2 inertial frame to joint_01 is 2m -->
<!-- moement arm from link_2 inertial frame to joint_12 is 0.5m -->
<pose>0 0 0 0 0 0</pose>
<axis>
<limit>
<lower>-0.000001</lower>
<upper>0.000001</upper>
<effort>1000.000000</effort>
<velocity>1000.000000</velocity>
</limit>
<dynamics>
<damping>0.000000</damping>
<friction>0.000000</friction>
</dynamics>
<xyz>0.000000 0.000000 1.000000</xyz>
</axis>
<sensor name="force_torque" type="force_torque">
<always_on>true</always_on>
<visualize>true</visualize>
<update_rate>30</update_rate>
</sensor>
<physics>
<provide_feedback>true</provide_feedback>
</physics>
</joint>
</model>
</world>
</sdf>