<!-- Model -->
<element name="model" required="*">
<description>The model element defines a complete robot or any other physical object.</description>
<attribute name="name" type="string" default="__default__" required="1">
<description>A unique name for the model. This name must not match another model in the world.</description>
</attribute>
<element name="static" type="bool" default="false" required="0">
<description>
If set to true, the model is immovable; i.e., a dynamics engine will not
update its position. The model's implicit frame will be attached to the
world's implicit frame. This holds even if this model is nested (or
included) by another model.
</description>
</element>
<element name="self_collide" type="bool" default="false" required="0">
<description>If set to true, all links in the model will collide with each other (except those connected by a joint). Can be overridden by the link or collision element self_collide property. Two links within a model will collide if link1.self_collide OR link2.self_collide. Links connected by a joint will never collide.</description>
</element>
<element name="allow_auto_disable" type="bool" default="true" required="0">
<description>Allows a model to auto-disable, which is means the physics engine can skip updating the model when the model is at rest. This parameter is only used by models with no joints.</description>
</element>
<include filename="frame.sdf" required="*"/>
<include filename="pose.sdf" required="0"/>
<include filename="link.sdf" required="*"/>
<include filename="joint.sdf" required="*"/>
<include filename="plugin.sdf" required="*"/>
<include filename="gripper.sdf" required="*"/>
<element name="include" required="*">
<description>Include resources from a URI. This can be used to nest models.</description>
<element name="uri" type="string" default="__default__" required="1">
<description>URI to a resource, such as a model</description>
</element>
<element name="pose" type="pose" default="0 0 0 0 0 0" required="0">
<description>Override the pose of the included model. A position and orientation in the global coordinate frame for the model. Position(x,y,z) and rotation (roll, pitch yaw) in the global coordinate frame.</description>
</element>
<include filename="plugin.sdf" required="*"/>
<element name="name" type="string" default="" required="0">
<description>Override the name of the included model.</description>
</element>
<element name="static" type="bool" default="false" required="0">
<description>Override the static value of the included model.</description>
</element>
</element>
<element name="model" ref="model" required="*">
<description>A nested model element</description>
<attribute name="name" type="string" default="__default__" required="1">
<description>A unique name for the model. This name must not match another nested model in the same level as this model.</description>
</attribute>
</element>
</element> <!-- End Model -->