This tutorial is about how to choose or tune physics related parameters, mainly focused on the physics parameters in Open Dynamics Engine(ODE).
This tutorial first explains physics related parameters that are applicable
to all the physics engines such as real_time_factor
and max_step_size
.
Then it explains with demonstration about how to use the parameters for solvers
,
constraints
, friction
. The order of parameters in this tutorial follows
the sdformat
specification definition here.
The parameters listed in this section are defined under the <physics>
tag
here. These are shared among
all physics engines.
type
: The type of the dynamics engine. Currently Gazebo supports 4 physics
engines: ode
, bullet
, simbody
and dart
. The default physics engine is ode
.
max_step_size
: The maximum time step size that can be taken by a
variable time-step solver (such as simbody) during simulation.
For physics engines with fixed-step solvers (like ODE), this is simply the time step size.
The default value in Gazebo is 0.001
seconds.
real_time_factor
: max_step_size x real_time_update_rate
sets an upper bound
of real_time_factor
. If real_time_factor < 1
the simulation is slower than real
time.
real_time_update_rate
: This is the frequency at which the simulation time steps
are advanced. The default value in Gazebo is 1000
Hz. Multiplying with the default
max_step_size
of 0.001
seconds gives a real_time_factor
of 1
. If real_time_update_rate
is set to 0
the simulation will run as fast as it can. If Gazebo is not able to update
at the desired rate, it will update as fast as it can, based on the computing power.
max_contacts
: The maximum number of contacts to be generated between two entities.
This value can be overwritten by the max_contacts
element nested under a collision
element. This is helpful to constrain the maximum number of contacts between two entities,
such as face-to-face collisions, with a potential sacrifice to the accuracy. The
max_contacts
parameter is especially helpful for trimesh objects. Another benefit of
max_contacts
parameter is that it allows users to allocate a fixed amount of memory
at the beginning to store contacts. No reallocation would happen since we have
allocated enough memory to store the maximum number of contacts possible.
The ODE user guide here includes the explanation to most physics related parameters. We will refer to this user guide when necessary.
solver
is an element nested under physics->ode->solver
in the sdformat
here
type
The type of the solvers in ODE. There are two types: world
and quick
.
world
step uses a direct method called Dantzig, and the quick
step uses an
iterative Projected Gauss-Seidel (PGS) method. world
step gives an accurate solution
if it is able to solve the problem, while quick
step depends on the number of
iterations to reach an accurate enough solution.
The following two videos show the double pendulum simulation with world
step and quick
step. It is clear that the contacts between the ground and the double pendulum base are
stable for world
step, while unstable (with the contacts disappearing and appearing for
each time step) for quick
step.
min_step_size
The minimum time duration which advances with each time step of a
variable time step solver.
This parameter is ignored by fixed-step size solvers.
The value of min_step_size
must be smaller than the max_step_size
under the
physics
element.
If this is left unspecified the default value will be the max_step_size
under physics
element.
iters
The number of iterations for the solver to run for each time step. In general, a
larger number results in better accuracy at the cost of slower simulation, but this is not
guaranteed. Note that this parameter is only meaningful to the ode quick
solver; world
solver
doesn't use this parameter.
precon_iters
This parameter only applies to the quick
solver. It is the number of
iterations used for preconditioning before solving the problem. The preconditioning strategy
is disabled by default and therefore this parameter is not used. As mentioned in the sdformat
specifications this is an experimental parameter.
sor
Successive Over-Relaxation parameter. This is used by quick
solver only.
use_dynamic_moi_rescaling
Flag to enable dynamic rescaling of moment of inertia in constrained
directions. The implementation of this feature is
here
constraints
is an element nested under physics->ode->constraints
in the sdformat
here
cfm
Constraint Force Mixing (CFM) is a square diagonal matrix. It adds a
small positive value to the matrix in the linear complementarity problem to be solved.
An explanation about cfm
is here.
This should be the first parameter to tune when the simulation is not stable, especially
one with intermittent contacts. CFM stablizes the simulation by converting a hard contact
to a soft one. Therefore, if the error metric to evaluate the solution still uses the violation
of the original hard contact CFM could limit the accuracy of the simulation. Figure 3-5 in
this paper
gives an explicit demonstration about this limitation. Due to the fact that CFM is always a
small positive value this limitation is always ignored.
erp
Error Reduction Parameter (ERP) specifies what proportion of the joint error will be fixed
during the next simulation step. The local ERP value nested under joints
overwrites that defined
global. A detailed explanation of erp
is here.
There is also proof about how the erp
, cfm
and kp
, kd
parameters are equivalent, i.e. cfm
and erp
simulates exactly the spring-damper behavior.
contact_max_correcting_vel
This is the same parameter as the max_vel
under collision->surface->contact
.
contact_max_correcting_vel
sets max_vel
globally. Given the following .world
file example:
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="default">
<physics type="ode">
<ode>
<solver>
<type>world</type>
</solver>
<constraints>
<contact_max_correcting_vel>0.1</contact_max_correcting_vel>
<contact_surface_layer>0.0001</contact_surface_layer>
</constraints>
</ode>
<max_step_size>0.001</max_step_size>
</physics>
<gravity>0.0 0.0 -9.81</gravity>
<include>
<uri>model://ground_plane</uri>
</include>
<include>
<uri>model://sun</uri>
</include>
<model name="sphere_1">
<pose>0.0 1.8 0.5 0.0 0.0 0.0</pose>
<link name="link_1">
<visual name="visual_sphere_1">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
<material>
<script>Gazebo/WoodPallet</script>
</material>
</visual>
<collision name="collision_sphere_1">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
<surface>
<contact>
<ode>
<max_vel>10</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
</surface>
</collision>
</link>
</model>
<model name="sphere_2">
<pose>0.0 0.0 0.5 0.0 0.0 0.0</pose>
<link name="link_2">
<visual name="visual_sphere_2">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
<material>
<script>Gazebo/WoodPallet</script>
</material>
</visual>
<collision name="collision_sphere_2">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
<surface>
<contact>
<ode>
<max_vel>1</max_vel>
<min_depth>0.01</min_depth>
</ode>
</contact>
</surface>
</collision>
</link>
</model>
</world>
</sdf>
In the above example, a global contact_max_correcting_vel
is defined with a value of 0.1
.
Model sphere_1
has a max_vel
of 10
and sphere_2
has a max_vel
of 1
. Whenever there
is a contact between sphere_1
and sphere_2
, ODE chose the minimum value of max_vel
of
the two entities that form the contact. In this case, max_vel
for the contact is
min(10, 1) = 1
; Finally this max_vel
is truncated by the contact_max_correcting_vel
defined globally, i.e. the max_vel
equals to min(1, 0.1) = 0.1
.
This simulation sets max_vel
to three different values for two spheres in collision. The
simulation starts with a contact at penetration depth of 0.5
. If we set max_vel=0
the
two spheres won't bounce and the velocity is zero after the penetration is corrected. If
max_vel
is set to 1
then the red sphere on the top would bounce at a speed no greater
than 1
, similarly for max_vel=10
. This is helpful to prevent the simulation from blowing
up, especially after the simulation corrects some penetration error of contacts.
contact_surface_layer
This is the same parameter as the min_depth
under collision->surface->contact
.
We use the same example as demonstrating contact_max_correcting_vel
since
contact_surface_layer
has similar truncation strategy. The penetration depth
between sphere_1
and sphere_2
is calculated as depth
at each time step. The
min_depth
value is decided by the minimum value between the two entities that
form the contact, and further truncated by the global contact_surface_layer
value.
In the above example: min_depth = min(min(0.001, 0.01), 0.0001) = 0.0001
.
With this min_depth
determined, penetration between the two entities is updated
depth = max(depth - min_depth, 0)
at each time step.
Three cases are shown in this video: the leftmost two spheres started with detaching mode,
i.e. they are not in contact at the beginning of the simulation. The red sphere on the top
starts falling due to gravity and forms a contact. In this case no penetration would happen
and therefore min_depth=0.5
doesn't play any role here. In the second case the two spheres
start with a contact and a penetration depth of 0.7
, min_depth=0
in this case. Therefore,
the simulation corrects the penetration depth of 0.7
. As for the third case, the two spheres
start with a contact and a penetration depth of 0.7
, min_depth=0.5
. Therefore, the
penetration depth will be updated by depth = max(depth-min_depth, 0)=0.2
and the simulation
corrects the new depth
of 0.2
. The two spheres stay with a remaining penetration depth
equal to the min_depth
.
For torsional friction in ODE, please refer to the tutorial here.
Contact friction parameters for each surface are specified in the SDFormat
friction
element nested under collision->surface->friction
here.
mu
Coefficient of friction along the first friction direction.
mu2
Coefficient of friction along the second friction direction.
For most cases, mu2
has same value with mu
.
fdir1
: 3-tuple unit vector specifying the direction of the first
friction direction corresponding to mu
in the collision local reference frame.
This picture shows how the friction cone is approximated with a pyramid model.
The direction of fdir1
, mu
and mu2
are marked. Whenever a contact forms,
the normal direction is decided and with a definition of fdir1
, contact coordinate
frame can be easily constructed with the third fdir2
as cross product of unit vector
along normal and fdir1
direction.
slip1
, slip2
: Force dependent slip direction 1 in collision local frame
with units of an inverse damper (m / s / N).
The interpretation of these parameters depends on the friction model in use
by the ODE solver, which is specified by the <friction_model>
parameter under
<physics><ode><solver>
and documented
here.
The default friction model is pyramid
, which decouples the friction
constraints into two 1-dimensional constraints that are solved independently.
This is illustrated in the following figure:
Valid values of the friction_model
include:
pyramid_model
: (default) friction constraints are decoupled into two
1-dimensional constraints that are solved independently.
The friction force limit is the product of the normal force and the
non-dimensional coefficients mu
and mu2
in each friction direction.
box_model
: friction forces are again decoupled into two 1-dimensional
constraints with a constant friction force limit that is independent of
the normal force.
For this model, the coefficients mu
and mu2
have units of Newtons
and represent the maximum friction force in each friction direction.
cone_model
: this model solves the coupled dynamic friction constraints
by choosing a friction direction parallel to the linear velocity
at the contact point.
Only the parameter <mu>
is used.
See gazebo pull request 1522
for the implementation of this feature.
The names of the friction cone and friction pyramid models derives from a geometric interpretation of the directions in which contact forces may point, as shown in the following figure. The angle of the cone/pyramid is set by the friction coefficient.
A fixed normal force corresponds to a circular slice from the cone, representing a limit on friction force magnitude in any direction. For the pyramid, a fixed normal force corresponds to a square slice representing the independent constraints in each direction. The friction cone model is more physically realistic, but the pyramid model is useful in some circumstances when anisotropic behavior is desired, such as in modeling longitudinal and lateral wheel friction separately (see the WheelSlipPlugin added in gazebo pull request 2950).
The difference between the box and cone friction models is visualized using the
friction_pyramid test world,
which has an array of boxes arrayed in a circle with an initial velocity going
away from the center of the circle.
Specifying cone_model
in that example world at
line 15
results in boxes that travel out radially as one would expect.
Since the pyramid friction model uses the world X-Y axes for its friction directions
by default, the velocity of some boxes is not aligned with these axes
and their behavior is different.
The velocity on each axis is treated independently, which is most evident when
considering a box with initial velocity not at 0, 45, or 90 degrees to a world
frame axis.
In these cases, one velocity component is much smaller than the other
and is dissipated to 0 while still moving in the other direction.
These boxes end up traveling parallel to one of the friction directions
for a duration before they eventually come to rest.
Specifying pyramid_model
in the example world illustrates this behavior.
contact
is an element nested under collision->surface->contact
in sdformat
here.
soft_cfm
Soft constraint force mixing. This is useful to make surfaces soft.
soft_erp
Soft error reduction parameter. This is useful to make surfaces soft.
kp
Dynamically 'stiffness'-equivalent coefficient for contact joints
kd
Dynamically 'damping'-equivalent coefficient for contact joints
kp
and kd
can be used to stabilize the contacts between two entities. The double
pendulum with quick
step has unstable intermittent contacts as we compared quick
step with world
step. If we add kp
and kd
parameter to the collision->surface->contact
between the ground and base the contacts will be stable as shown in this following video.
<collision name="col_plate_on_ground">
<pose>0 0 0.01 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.8</radius>
<length>0.02</length>
</cylinder>
</geometry>
<surface>
<contact>
<ode>
<kp>1e15</kp>
<kd>1e13</kd>
</ode>
</contact>
</surface>
</collision>
max_vel
Maximum correction velocity for contacts. If the predicted velocity for the
next simulation step is larger than this value it will be truncated to this value.
The combination usage with contact_max_correcting_vel
is demonstrated earlier
min_depth
If the penetration depth is no greater than the value of min_depth
, then no
contact force would be applied. Otherwise, contact force will be applied to
correct the portion of the penetration with a value of penetration depth minus
min_depth
. The remaining min_depth
penetration would stay.
All the world files to generate the demonstration videos are accessible here.