Skip to content

Commit 7cab1bb

Browse files
committed
Example world: use 1.11 and auto inertials
Adjust geometry slightly and set density to retain the same mass values and approximately the same inertia matrix. Signed-off-by: Steve Peters <scpeters@openrobotics.org>
1 parent e60bb9a commit 7cab1bb

File tree

1 file changed

+14
-54
lines changed

1 file changed

+14
-54
lines changed

examples/worlds/set_model_state.sdf

+14-54
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@
55
The initial joint position should be 90 degrees, and the initial joint
66
velocity should be -30 degrees / second.
77
-->
8-
<sdf version="1.6">
8+
<sdf version="1.11">
99
<world name="set_model_state">
1010
<plugin
1111
filename="gz-sim-physics-system"
@@ -56,25 +56,15 @@
5656
</link>
5757
</model>
5858
<model name="model_state_example_degrees">
59-
<pose>0 0 0.005 0 0 0</pose>
59+
<pose>0 0 0.04 0 0 0</pose>
6060
<link name="base_link">
61-
<pose>0.0 0.0 0.0 0 0 0</pose>
62-
<inertial>
63-
<inertia>
64-
<ixx>2.501</ixx>
65-
<ixy>0</ixy>
66-
<ixz>0</ixz>
67-
<iyy>2.501</iyy>
68-
<iyz>0</iyz>
69-
<izz>5</izz>
70-
</inertia>
71-
<mass>120.0</mass>
61+
<inertial auto="true">
62+
<density>6000</density>
7263
</inertial>
7364
<visual name="base_visual">
74-
<pose>0.0 0.0 0.0 0 0 0</pose>
7565
<geometry>
7666
<box>
77-
<size>0.5 0.5 0.01</size>
67+
<size>0.5 0.5 0.08</size>
7868
</box>
7969
</geometry>
8070
<material>
@@ -84,27 +74,17 @@
8474
</material>
8575
</visual>
8676
<collision name="base_collision">
87-
<pose>0.0 0.0 0.0 0 0 0</pose>
8877
<geometry>
8978
<box>
90-
<size>0.5 0.5 0.01</size>
79+
<size>0.5 0.5 0.08</size>
9180
</box>
9281
</geometry>
9382
</collision>
9483
</link>
9584
<link name="rotor">
9685
<pose>0.0 0.0 1.0 0.0 0 0</pose>
97-
<inertial>
98-
<pose>0.0 0.0 0.0 0 0 0</pose>
99-
<inertia>
100-
<ixx>0.032</ixx>
101-
<ixy>0</ixy>
102-
<ixz>0</ixz>
103-
<iyy>0.032</iyy>
104-
<iyz>0</iyz>
105-
<izz>0.00012</izz>
106-
</inertia>
107-
<mass>0.6</mass>
86+
<inertial auto="true">
87+
<density>192</density>
10888
</inertial>
10989
<visual name="visual">
11090
<geometry>
@@ -155,23 +135,13 @@
155135
<model name="model_state_example_radians">
156136
<pose>1.0 0 0.005 0 0 0</pose>
157137
<link name="base_link">
158-
<pose>0.0 0.0 0.0 0 0 0</pose>
159-
<inertial>
160-
<inertia>
161-
<ixx>2.501</ixx>
162-
<ixy>0</ixy>
163-
<ixz>0</ixz>
164-
<iyy>2.501</iyy>
165-
<iyz>0</iyz>
166-
<izz>5</izz>
167-
</inertia>
168-
<mass>120.0</mass>
138+
<inertial auto="true">
139+
<density>6000</density>
169140
</inertial>
170141
<visual name="base_visual">
171-
<pose>0.0 0.0 0.0 0 0 0</pose>
172142
<geometry>
173143
<box>
174-
<size>0.5 0.5 0.01</size>
144+
<size>0.5 0.5 0.08</size>
175145
</box>
176146
</geometry>
177147
<material>
@@ -181,27 +151,17 @@
181151
</material>
182152
</visual>
183153
<collision name="base_collision">
184-
<pose>0.0 0.0 0.0 0 0 0</pose>
185154
<geometry>
186155
<box>
187-
<size>0.5 0.5 0.01</size>
156+
<size>0.5 0.5 0.08</size>
188157
</box>
189158
</geometry>
190159
</collision>
191160
</link>
192161
<link name="rotor">
193162
<pose>0.0 0.0 1.0 0.0 0 0</pose>
194-
<inertial>
195-
<pose>0.0 0.0 0.0 0 0 0</pose>
196-
<inertia>
197-
<ixx>0.032</ixx>
198-
<ixy>0</ixy>
199-
<ixz>0</ixz>
200-
<iyy>0.032</iyy>
201-
<iyz>0</iyz>
202-
<izz>0.00012</izz>
203-
</inertia>
204-
<mass>0.6</mass>
163+
<inertial auto="true">
164+
<density>192</density>
205165
</inertial>
206166
<visual name="visual">
207167
<geometry>

0 commit comments

Comments
 (0)