Skip to content

Commit f66701e

Browse files
authored
shapes.sdf example: bump to 1.12, add cone shape (#2448)
Also move the example command to a CDATA block to use proper XML syntax. Signed-off-by: Steve Peters <scpeters@openrobotics.org>
1 parent 0d78194 commit f66701e

File tree

1 file changed

+40
-8
lines changed

1 file changed

+40
-8
lines changed

examples/worlds/shapes.sdf

+40-8
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,13 @@
11
<?xml version="1.0" ?>
2-
<!--
3-
4-
Try moving a model:
5-
6-
gz service -s /world/shapes/set_pose --reqtype gz.msgs.Pose --reptype gz.msgs.Boolean --timeout 300 --req 'name: "box", position: {z: 5.0}'
7-
8-
-->
9-
<sdf version="1.6">
2+
<sdf version="1.12">
3+
<!--
4+
Try moving a model using the command in the following CDATA block::
5+
-->
6+
<![CDATA[
7+
gz service -s /world/shapes/set_pose \
8+
--reqtype gz.msgs.Pose --reptype gz.msgs.Boolean \
9+
--timeout 300 --req 'name: "box", position: {z: 5.0}'
10+
]]>
1011
<world name="shapes">
1112
<scene>
1213
<ambient>1.0 1.0 1.0</ambient>
@@ -240,5 +241,36 @@ Try moving a model:
240241
</visual>
241242
</link>
242243
</model>
244+
245+
<model name="cone">
246+
<pose>0 4.5 0.5 0 0 0</pose>
247+
<link name="cone_link">
248+
<inertial auto="true">
249+
<density>1</density>
250+
</inertial>
251+
<collision name="cone_collision">
252+
<geometry>
253+
<cone>
254+
<radius>0.5</radius>
255+
<length>1.0</length>
256+
</cone>
257+
</geometry>
258+
</collision>
259+
260+
<visual name="cone_visual">
261+
<geometry>
262+
<cone>
263+
<radius>0.5</radius>
264+
<length>1.0</length>
265+
</cone>
266+
</geometry>
267+
<material>
268+
<ambient>1 0.47 0 1</ambient>
269+
<diffuse>1 0.47 0 1</diffuse>
270+
<specular>1 0.47 0 1</specular>
271+
</material>
272+
</visual>
273+
</link>
274+
</model>
243275
</world>
244276
</sdf>

0 commit comments

Comments
 (0)