ppovb5fc7/sdformat/sdf/1.6/physics.sdf

226 lines
13 KiB
Plaintext

<!-- Physics -->
<element name="physics" required="1">
<description>The physics tag specifies the type and properties of the dynamics engine.</description>
<attribute name="name" type="string" default="default_physics" required="0">
<description>The name of this set of physics parameters.</description>
</attribute>
<attribute name="default" type="bool" default="false" required="0">
<description>If true, this physics element is set as the default physics profile for the world. If multiple default physics elements exist, the first element marked as default is chosen. If no default physics element exists, the first physics element is chosen.</description>
</attribute>
<attribute name="type" type="string" default="ode" required="1">
<description>The type of the dynamics engine. Current options are ode, bullet, simbody and rtql8. Defaults to ode if left unspecified.</description>
</attribute>
<element name="max_step_size" type="double" default="0.001" required="1">
<description>Maximum time step size at which every system in simulation can interact with the states of the world. (was physics.sdf's dt).</description>
</element>
<!-- real_time_factor (simulation speedup) might be more intuitive to end
users than real_time_update_rate -->
<element name="real_time_factor" type="double" default="1.0" required="1">
<description>target simulation speedup factor, defined by ratio of simulation time to real-time.</description>
</element>
<!-- to be deprecated by real_time_factor -->
<element name="real_time_update_rate" type="double" default="1000" required="1">
<description>Rate at which to update the physics engine (UpdatePhysics calls per real-time second). (was physics.sdf's update_rate).</description>
</element>
<element name="max_contacts" type="int" default="20" required="0">
<description>Maximum number of contacts allowed between two entities. This value can be over ridden by a max_contacts element in a collision element.</description>
</element>
<element name="simbody" required="0">
<description>Simbody specific physics properties</description>
<element name="min_step_size" type="double" default="0.0001" required="0">
<description>(Currently not used in simbody) The time duration which advances with each iteration of the dynamics engine, this has to be no bigger than max_step_size under physics block. If left unspecified, min_step_size defaults to max_step_size.</description>
</element>
<element name="accuracy" type="double" default="1e-3" required="0">
<description>Roughly the relative error of the system.
-LOG(accuracy) is roughly the number of significant digits.</description>
</element>
<element name="max_transient_velocity" type="double"
default="0.01" required="0">
<description>Tolerable "slip" velocity allowed by the solver when static
friction is supposed to hold object in place.</description>
</element>
<element name="contact" required="0">
<description><![CDATA[
Relationship among dissipation, coef. restitution, etc.
d = dissipation coefficient (1/velocity)
vc = capture velocity (velocity where e=e_max)
vp = plastic velocity (smallest v where e=e_min) > vc
Assume real COR=1 when v=0.
e_min = given minimum COR, at v >= vp (a.k.a. plastic_coef_restitution)
d = slope = (1-e_min)/vp
OR, e_min = 1 - d*vp
e_max = maximum COR = 1-d*vc, reached at v=vc
e = 0, v <= vc
= 1 - d*v, vc < v < vp
= e_min, v >= vp
dissipation factor = d*min(v,vp) [compliant]
cor = e [rigid]
Combining rule e = 0, e1==e2==0
= 2*e1*e2/(e1+e2), otherwise]]>
</description>
<element name="stiffness" type="double" default="1e8" required="0">
<description>Default contact material stiffness
(force/dist or torque/radian).</description>
</element>
<element name="dissipation" type="double" default="100" required="0">
<description>dissipation coefficient to be used in compliant contact;
if not given it is (1-min_cor)/plastic_impact_velocity</description>
</element>
<element name="plastic_coef_restitution" type="double"
default="0.5" required="0">
<description>this is the COR to be used at high velocities for rigid
impacts; if not given it is 1 - dissipation*plastic_impact_velocity
</description>
</element>
<element name="plastic_impact_velocity" type="double"
default="0.5" required="0">
<description>smallest impact velocity at which min COR is reached; set
to zero if you want the min COR always to be used</description>
</element>
<element name="static_friction" type="double" default="0.9" required="0">
<description>static friction (mu_s) as described by this plot: http://gazebosim.org/wiki/File:Stribeck_friction.png</description>
</element>
<element name="dynamic_friction" type="double" default="0.9" required="0">
<description>dynamic friction (mu_d) as described by this plot: http://gazebosim.org/wiki/File:Stribeck_friction.png</description>
</element>
<element name="viscous_friction" type="double" default="0.0" required="0">
<description>viscous friction (mu_v) with units of (1/velocity) as described by this plot: http://gazebosim.org/wiki/File:Stribeck_friction.png</description>
</element>
<element name="override_impact_capture_velocity" type="double"
default="0.001" required="0">
<description>for rigid impacts only, impact velocity at which
COR is set to zero; normally inherited from global default but can
be overridden here. Combining rule: use larger velocity</description>
</element>
<element name="override_stiction_transition_velocity" type="double"
default="0.001" required="0">
<description>This is the largest slip velocity at which
we'll consider a transition to stiction. Normally inherited
from a global default setting. For a continuous friction model
this is the velocity at which the max static friction force
is reached. Combining rule: use larger velocity</description>
</element>
</element>
</element>
<element name="bullet" required="0">
<description>Bullet specific physics properties</description>
<element name="solver" required="1">
<description></description>
<element name="type" type="string" default="sequential_impulse" required="1">
<description>One of the following types: sequential_impulse only.</description>
</element>
<element name="min_step_size" type="double" default="0.0001" required="0">
<description>The time duration which advances with each iteration of the dynamics engine, this has to be no bigger than max_step_size under physics block. If left unspecified, min_step_size defaults to max_step_size.</description>
</element>
<element name="iters" type="int" default="50" required="1">
<description>Number of iterations for each step. A higher number produces greater accuracy at a performance cost.</description>
</element>
<element name="sor" type="double" default="1.3" required="1">
<description>Set the successive over-relaxation parameter.</description>
</element>
</element> <!-- End Solver -->
<element name="constraints" required="1">
<description>Bullet constraint parameters.</description>
<element name="cfm" type="double" default="0" required="1">
<description>Constraint force mixing parameter. See the ODE page for more information.</description>
</element>
<element name="erp" type="double" default="0.2" required="1">
<description>Error reduction parameter. See the ODE page for more information.</description>
</element>
<element name="contact_surface_layer" type="double" default="0.001" required="1">
<description>The depth of the surface layer around all geometry objects. Contacts are allowed to sink into the surface layer up to the given depth before coming to rest. The default value is zero. Increasing this to some small value (e.g. 0.001) can help prevent jittering problems due to contacts being repeatedly made and broken.</description>
</element>
<element name="split_impulse" type="bool" default="1" required="1">
<description>Similar to ODE's max_vel implementation. See http://web.archive.org/web/20120430155635/http://bulletphysics.org/mediawiki-1.5.8/index.php/BtContactSolverInfo#Split_Impulse for more information.</description>
</element>
<element name="split_impulse_penetration_threshold" type="double" default="-0.01" required="1">
<description>Similar to ODE's max_vel implementation. See http://web.archive.org/web/20120430155635/http://bulletphysics.org/mediawiki-1.5.8/index.php/BtContactSolverInfo#Split_Impulse for more information.</description>
</element>
</element> <!-- End Constraints -->
</element>
<element name="ode" required="0">
<description>ODE specific physics properties</description>
<element name="solver" required="1">
<description></description>
<element name="type" type="string" default="quick" required="1">
<description>One of the following types: world, quick</description>
</element>
<element name="min_step_size" type="double" default="0.0001" required="0">
<description>The time duration which advances with each iteration of the dynamics engine, this has to be no bigger than max_step_size under physics block. If left unspecified, min_step_size defaults to max_step_size.</description>
</element>
<element name="island_threads" type="int" default="0" required="0">
<description>Number of threads to use for "islands" of disconnected models.</description>
</element>
<element name="iters" type="int" default="50" required="1">
<description>Number of iterations for each step. A higher number produces greater accuracy at a performance cost.</description>
</element>
<element name="precon_iters" type="int" default="0" required="0">
<description>Experimental parameter.</description>
</element>
<element name="sor" type="double" default="1.3" required="1">
<description>Set the successive over-relaxation parameter.</description>
</element>
<element name="thread_position_correction" type="bool" default="0" required="0">
<description>Flag to use threading to speed up position correction computation.</description>
</element>
<element name="use_dynamic_moi_rescaling" type="bool" default="0" required="1">
<description>
Flag to enable dynamic rescaling of moment of inertia in constrained directions.
See gazebo pull request 1114 for the implementation of this feature.
https://bitbucket.org/osrf/gazebo/pull-request/1114
</description>
</element>
<element name="friction_model" type="string" default="pyramid_model" required="0">
<description>
Name of ODE friction model to use. Valid values include:
pyramid_model: (default) friction forces limited in two directions
in proportion to normal force.
box_model: friction forces limited to constant in two directions.
cone_model: friction force magnitude limited in proportion to normal force.
See gazebo pull request 1522 for the implementation of this feature.
https://bitbucket.org/osrf/gazebo/pull-request/1522
https://bitbucket.org/osrf/gazebo/commits/8c05ad64967c
</description>
</element>
</element> <!-- End Solver -->
<element name="constraints" required="1">
<description>ODE constraint parameters.</description>
<element name="cfm" type="double" default="0" required="1">
<description>Constraint force mixing parameter. See the ODE page for more information.</description>
</element>
<element name="erp" type="double" default="0.2" required="1">
<description>Error reduction parameter. See the ODE page for more information.</description>
</element>
<element name="contact_max_correcting_vel" type="double" default="100.0" required="1">
<description>The maximum correcting velocities allowed when resolving contacts.</description>
</element>
<element name="contact_surface_layer" type="double" default="0.001" required="1">
<description>The depth of the surface layer around all geometry objects. Contacts are allowed to sink into the surface layer up to the given depth before coming to rest. The default value is zero. Increasing this to some small value (e.g. 0.001) can help prevent jittering problems due to contacts being repeatedly made and broken.</description>
</element>
</element> <!-- End Constraints -->
</element> <!-- ODE -->
</element> <!-- Physics -->