Skip to content

Commit 9f74919

Browse files
authored
Lower sdf version to 1.6 (gazebosim#624)
Using sdf version 1.7 was causing issues when running on gazebo9
1 parent a1b6944 commit 9f74919

File tree

1 file changed

+40
-39
lines changed

1 file changed

+40
-39
lines changed

models/iris/iris.sdf.jinja

+40-39
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,8 @@
11
<!-- DO NOT EDIT: Generated from iris.sdf.jinja -->
2-
<sdf version='1.7'>
2+
<sdf version='1.6'>
33
<model name='iris'>
44
<link name='base_link'>
5+
<pose>0 0 0 0 0 0</pose>
56
<inertial>
67
<pose>0 0 0 0 0 0</pose>
78
<mass>1.5</mass>
@@ -51,26 +52,8 @@
5152
<gravity>1</gravity>
5253
<velocity_decay/>
5354
</link>
54-
<joint name='/imu_joint' type='revolute'>
55-
<pose relative_to='base_link'>0 0 0 0 0 0</pose>
56-
<parent>base_link</parent>
57-
<child>/imu_link</child>
58-
<axis>
59-
<xyz>1 0 0</xyz>
60-
<limit>
61-
<lower>0</lower>
62-
<upper>0</upper>
63-
<effort>0</effort>
64-
<velocity>0</velocity>
65-
</limit>
66-
<dynamics>
67-
<spring_reference>0</spring_reference>
68-
<spring_stiffness>0</spring_stiffness>
69-
</dynamics>
70-
</axis>
71-
</joint>
7255
<link name='/imu_link'>
73-
<pose relative_to='/imu_joint'>0 0 0 0 0 0</pose>
56+
<pose>0 0 0 0 0 0</pose>
7457
<inertial>
7558
<pose>0 0 0 0 0 0</pose>
7659
<mass>0.015</mass>
@@ -84,24 +67,26 @@
8467
</inertia>
8568
</inertial>
8669
</link>
87-
<joint name='rotor_0_joint' type='revolute'>
88-
<pose relative_to='base_link'>0.13 -0.22 0.023 0 0 0</pose>
70+
<joint name='/imu_joint' type='revolute'>
71+
<child>/imu_link</child>
8972
<parent>base_link</parent>
90-
<child>rotor_0</child>
9173
<axis>
92-
<xyz>0 0 1</xyz>
74+
<xyz>1 0 0</xyz>
9375
<limit>
94-
<lower>-1e+16</lower>
95-
<upper>1e+16</upper>
76+
<lower>0</lower>
77+
<upper>0</upper>
78+
<effort>0</effort>
79+
<velocity>0</velocity>
9680
</limit>
9781
<dynamics>
9882
<spring_reference>0</spring_reference>
9983
<spring_stiffness>0</spring_stiffness>
10084
</dynamics>
85+
<use_parent_model_frame>1</use_parent_model_frame>
10186
</axis>
10287
</joint>
10388
<link name='rotor_0'>
104-
<pose relative_to='rotor_0_joint'>0 0 0 0 0 0</pose>
89+
<pose>0.13 -0.22 0.023 0 0 0</pose>
10590
<inertial>
10691
<pose>0 0 0 0 0 0</pose>
10792
<mass>0.005</mass>
@@ -149,10 +134,9 @@
149134
<gravity>1</gravity>
150135
<velocity_decay/>
151136
</link>
152-
<joint name='rotor_1_joint' type='revolute'>
153-
<pose relative_to='base_link'>-0.13 0.2 0.023 0 0 0</pose>
137+
<joint name='rotor_0_joint' type='revolute'>
138+
<child>rotor_0</child>
154139
<parent>base_link</parent>
155-
<child>rotor_1</child>
156140
<axis>
157141
<xyz>0 0 1</xyz>
158142
<limit>
@@ -163,10 +147,11 @@
163147
<spring_reference>0</spring_reference>
164148
<spring_stiffness>0</spring_stiffness>
165149
</dynamics>
150+
<use_parent_model_frame>1</use_parent_model_frame>
166151
</axis>
167152
</joint>
168153
<link name='rotor_1'>
169-
<pose relative_to='rotor_1_joint'>0 0 0 0 0 0</pose>
154+
<pose>-0.13 0.2 0.023 0 0 0</pose>
170155
<inertial>
171156
<pose>0 0 0 0 0 0</pose>
172157
<mass>0.005</mass>
@@ -214,10 +199,9 @@
214199
<gravity>1</gravity>
215200
<velocity_decay/>
216201
</link>
217-
<joint name='rotor_2_joint' type='revolute'>
218-
<pose relative_to='base_link'>0.13 0.22 0.023 0 0 0</pose>
202+
<joint name='rotor_1_joint' type='revolute'>
203+
<child>rotor_1</child>
219204
<parent>base_link</parent>
220-
<child>rotor_2</child>
221205
<axis>
222206
<xyz>0 0 1</xyz>
223207
<limit>
@@ -228,10 +212,11 @@
228212
<spring_reference>0</spring_reference>
229213
<spring_stiffness>0</spring_stiffness>
230214
</dynamics>
215+
<use_parent_model_frame>1</use_parent_model_frame>
231216
</axis>
232217
</joint>
233218
<link name='rotor_2'>
234-
<pose relative_to='rotor_2_joint'>0 0 0 0 0 0</pose>
219+
<pose>0.13 0.22 0.023 0 0 0</pose>
235220
<inertial>
236221
<pose>0 0 0 0 0 0</pose>
237222
<mass>0.005</mass>
@@ -279,10 +264,9 @@
279264
<gravity>1</gravity>
280265
<velocity_decay/>
281266
</link>
282-
<joint name='rotor_3_joint' type='revolute'>
283-
<pose relative_to='base_link'>-0.13 -0.2 0.023 0 0 0</pose>
267+
<joint name='rotor_2_joint' type='revolute'>
268+
<child>rotor_2</child>
284269
<parent>base_link</parent>
285-
<child>rotor_3</child>
286270
<axis>
287271
<xyz>0 0 1</xyz>
288272
<limit>
@@ -293,10 +277,11 @@
293277
<spring_reference>0</spring_reference>
294278
<spring_stiffness>0</spring_stiffness>
295279
</dynamics>
280+
<use_parent_model_frame>1</use_parent_model_frame>
296281
</axis>
297282
</joint>
298283
<link name='rotor_3'>
299-
<pose relative_to='rotor_3_joint'>0 0 0 0 0 0</pose>
284+
<pose>-0.13 -0.2 0.023 0 0 0</pose>
300285
<inertial>
301286
<pose>0 0 0 0 0 0</pose>
302287
<mass>0.005</mass>
@@ -344,6 +329,22 @@
344329
<gravity>1</gravity>
345330
<velocity_decay/>
346331
</link>
332+
<joint name='rotor_3_joint' type='revolute'>
333+
<child>rotor_3</child>
334+
<parent>base_link</parent>
335+
<axis>
336+
<xyz>0 0 1</xyz>
337+
<limit>
338+
<lower>-1e+16</lower>
339+
<upper>1e+16</upper>
340+
</limit>
341+
<dynamics>
342+
<spring_reference>0</spring_reference>
343+
<spring_stiffness>0</spring_stiffness>
344+
</dynamics>
345+
<use_parent_model_frame>1</use_parent_model_frame>
346+
</axis>
347+
</joint>
347348
<plugin name='rosbag' filename='libgazebo_multirotor_base_plugin.so'>
348349
<robotNamespace/>
349350
<linkName>base_link</linkName>

0 commit comments

Comments
 (0)