Skip to content

Commit

Permalink
shapes.sdf example: bump to 1.12, add cone shape (#2448)
Browse files Browse the repository at this point in the history
Also move the example command to a CDATA block to use
proper XML syntax.

Signed-off-by: Steve Peters <[email protected]>
  • Loading branch information
scpeters authored Jun 17, 2024
1 parent 0d78194 commit f66701e
Showing 1 changed file with 40 additions and 8 deletions.
48 changes: 40 additions & 8 deletions examples/worlds/shapes.sdf
Original file line number Diff line number Diff line change
@@ -1,12 +1,13 @@
<?xml version="1.0" ?>
<!--
Try moving a model:
gz service -s /world/shapes/set_pose --reqtype gz.msgs.Pose --reptype gz.msgs.Boolean --timeout 300 --req 'name: "box", position: {z: 5.0}'
-->
<sdf version="1.6">
<sdf version="1.12">
<!--
Try moving a model using the command in the following CDATA block::
-->
<![CDATA[
gz service -s /world/shapes/set_pose \
--reqtype gz.msgs.Pose --reptype gz.msgs.Boolean \
--timeout 300 --req 'name: "box", position: {z: 5.0}'
]]>
<world name="shapes">
<scene>
<ambient>1.0 1.0 1.0</ambient>
Expand Down Expand Up @@ -240,5 +241,36 @@ Try moving a model:
</visual>
</link>
</model>

<model name="cone">
<pose>0 4.5 0.5 0 0 0</pose>
<link name="cone_link">
<inertial auto="true">
<density>1</density>
</inertial>
<collision name="cone_collision">
<geometry>
<cone>
<radius>0.5</radius>
<length>1.0</length>
</cone>
</geometry>
</collision>

<visual name="cone_visual">
<geometry>
<cone>
<radius>0.5</radius>
<length>1.0</length>
</cone>
</geometry>
<material>
<ambient>1 0.47 0 1</ambient>
<diffuse>1 0.47 0 1</diffuse>
<specular>1 0.47 0 1</specular>
</material>
</visual>
</link>
</model>
</world>
</sdf>

0 comments on commit f66701e

Please sign in to comment.