Skip to content

User Manual

xiss burg edited this page Mar 13, 2024 · 84 revisions

This document shows how to use Edyn in practice.

Introduction

Edyn is a real-time physics simulation engine focused on constrained rigid body simulation. It seeks to have the capacity to simulate very large worlds leveraging multithreading and distributed simulation.

It operates in conjunction with an entt::registry which makes it ideal for any ECS-oriented project that uses EnTT. One of the great advantages is that no weird conversions must be done to and from the registry and an object-oriented physics engine. All the relevant physics information is associated with the entity, i.e. the edyn::present_position and edyn::present_orientation components can be obtained from the registry and used to render the entity and the edyn::linvel and edyn::angvel components hold the velocity of the rigid body and can be used for any other purposes such as motion blur or Doppler effect.

Features

  • Discrete collision detection using SAT. Collision detection APIs can be used in isolation.
  • Shapes:
    • Box.
    • Sphere.
    • Cylinder, oriented in any of the three coordinate axes.
    • Capsule, oriented in any of the three coordinate axes.
    • Convex polyhedron.
    • Compound, which allows any of the above to be combined into a single shape, which can be concave.
    • Concave triangle mesh using Voronoi regions to prevent internal edge collisions. Can only be used for static entities such as terrain.
    • Paged triangle mesh which loads sub meshes on demand. To be used for large terrains.
  • Constraints:
    • Contact: the most important constraint which prevents rigid bodies from penetrating. They're created internally in the narrow-phase collision detection.
    • Distance constraint: keeps the distance between two points on the bodies constant.
    • Soft distance constraint: similar to distance constraint but it acts as a spring.
    • Generic constraint: allows individual degrees of freedom to be constrained.
    • Hinge constraint: constrains two bodies around an axis passing through a point.
    • Point constraint: constrains two bodies at a point.
    • CV-joint constraint: constant velocity joint.
    • Cone constraint: constrains a point in one body to stay inside a cone in the other body. Used primarily in rag dolls.
    • Gravity constraint: applies gravitational force between two entities following Newton's law of gravitation.
    • Null constraint: a constraint that does nothing. It can be used to create an edge in the entity graph and ensure that two entities always live in the same island.
  • Sequential-Impulses constraint solver.
  • Ray-casting.
  • Collision filtering.
  • Collision events.
  • Networked physics.

The physics step

This is the order of major updates:

  1. Run broad-phase collision detection. Contact manifolds are created and destroyed in this step.
  2. Run narrow-phase collision detection. Closest point calculations are performed and contact points are created.
  3. Apply external forces such as gravity.
  4. Solve constraints.
  5. Apply constraint impulses.
  6. Integrate velocities to obtain new positions and orientations.

Collision events are recorded in step #2 but are delivered at the end of the step. This ensures the collision impulse calculated in step #4 will be available by the time the collision event is processed by the application.

Simulation islands

Edyn builds a graph where rigid bodies are nodes and constraints are edges and finds the connected components in this graph to split up the rigid bodies and constraints in subsets which can be simulated in isolation because they do not interact with entities in other connected components. These connected components are also known as islands. As constraints are created and destroyed, the island manager checks if any connected components have merged or split and proceeds to destroy or create new islands.

Rigid bodies in different islands do not affect the motion of each other, which creates the opportunity for parallelization of certain tasks.

When all rigid bodies in an island comes to rest, the island is set to sleep, i.e. a edyn::sleeping_tag is assigned to all entities in that island.

Execution modes

Edyn can be executed in sequential or asynchronous mode, more specifically:

  • Sequential: runs the simulation in the calling thread. All the work is done in the call to edyn::update. It will only dispatch jobs to run in a background thread for non-blocking tasks such as loading pages in a edyn::paged_triangle_mesh.
  • Sequential multi-threaded: identical to the sequential mode except that it will conditionally parallelize parts of the update cycle, mostly using edyn::parallel_for in tasks such as narrowphase collision detection and solving constraints per island.
  • Asynchronous: offloads as much work as possible to background threads to make the call to edyn::update as lightweight as possible. This is the highest performing execution mode since it frees up the main thread which generally has a lot more to do than just physics simulation. Using the engine in this mode requires extra steps due to the asynchronous nature of many operations. See the asynchronous execution section for more details.

The asynchronous mode is the default.

Creating a scene and running a simulation

Edyn can be run in one more EnTT registries. Call edyn::attach(registry) to make a entt::registry ready to be used for physics simulation, and then create rigid bodies and constraints in the registry. In the main loop of the application, edyn::update(registry) must be called to step the simulation forward.

// Initialization.
entt::registry registry;
edyn::attach(registry);

// Create floor
auto floor_def = edyn::rigidbody_def();
floor_def.kind = edyn::rigidbody_kind::rb_static;
floor_def.material->restitution = 1;
floor_def.material->friction = 0.5;
// Plane at the origin with normal pointing upwards.
floor_def.shape = edyn::plane_shape{{0, 1, 0}, 0};
edyn::make_rigidbody(registry, floor_def);

// Create dynamic rigid body.
auto def = edyn::rigidbody_def();
def.material->friction = 0.8;
def.mass = 10;
def.restitution = 0;
// Box with 0.2 half-length in all dimensions.
def.shape = edyn::box_shape{0.2, 0.2, 0.2};
auto entity = edyn::make_rigidbody(registry, def);
// Extra components of your own can be assigned to the returned entity.
// An existing entity can be passed to `edyn::make_rigidbody` as well, such as:
// auto entity = registry.create();
// edyn::make_rigidbody(entity, registry, def);

// Main loop.
while (true) {
    edyn::update(registry);
    // Do something with the physics components such as rendering.
}

// Finish.
edyn::detach(registry);

The edyn::init() function can take an edyn::init_config as parameter containing initialization options. Currently the only setting available is the execution mode which determines whether the simulation runs in-place (i.e. sequential) or in a background thread (i.e. asynchronous). More info in the execution modes section.

All rigid bodies have the edyn::position and edyn::orientation components, however these should not be used for rendering or else the result will have noticeable stutter. That is because the simulation always runs in steps of fixed delta time, thus the physics state will rarely match what the state would be at the current point in time. To ameliorate these issues, interpolation/extrapolation is done to align the state of all rigid bodies to the same point in time, and that state is available in the edyn::present_position and edyn::present_orientation components.

The edyn::orientation and edyn::present_orientation components are derived from edyn::quaternion. It's important to note that the elements of edyn::quaternion are ordered as x y z w, which could be different of the graphics engine you might be interfacing with. Some engines use the w x y z order, thus be careful to not get these mixed up.

Rigid bodies can be of three types:

  • Dynamic: the default type in a edyn::rigidbody_def, represents a rigid body that has procedurally calculated motion.
  • Static: a rigid body which does not move. It has infinite mass and inertia.
  • Kinematic: a rigid body with infinite mass and inertia which can be moved programmatically.

The initial type is specified in the edyn::rigidbody_def::kind property and can be changed during run time using edyn::rigidbody_set_kind.

Some shapes can only be used with static rigid bodies, i.e. edyn::plane_shape, edyn::mesh_shape and edyn::paged_mesh_shape. There's no moment of inertia calculation for these shapes and there's no collision detection algorithm implemented between them. They also ignore any transforms applied to the rigid body (i.e. edyn::position and edyn::orientation) for performance and complexity reasons.

Shapes are optional. Rigid bodies without a shape are termed amorphous and do not take part in collision detection. They can be constrained with other rigid bodies however and be used as internal components of a machine such as drive-train components of a vehicle.

Moment of inertia is calculated from shape and mass by default. The edyn::rigidbody_def has an optional custom inertia that can be assigned. If the body is dynamic and has no shape, the custom inertia must be assigned.

The material is optional. It is non-empty by default. If reset (i.e. def.material.reset()), the rigid body will not respond to collisions, i.e. collisions will be detected and contact points will be generated but no edyn::contact_constraint will be created. These kinds of bodies are known as sensors because they can be used with collision events to detect when another body enters a certain volume in the world.

To destroy a rigid body simply destroy the entity, such as registry.destroy(entity). To destroy a rigid body while preserving the entity, call edyn::clear_rigidbody. This enables one entity to be used for your own particular purposes other than just being a rigid body.

Creating constraints

Constraints can be created between a pair of rigid bodies to tie their motion in some way. Use the edyn::make_constraint function to create constraints. It takes a pair of rigid body entities and an optional setup function as arguments. It ensures the properties assigned are propagated to the simulation worker when running in asynchronous execution mode.

auto def = edyn::rigidbody_def();
// Configure rigid body...
auto bodyA = edyn::make_rigidbody(registry, def);
auto bodyB = edyn::make_rigidbody(registry, def);
// Create a point pivot. It returns an (entity, component) pair.
auto point_entity = edyn::make_constraint<edyn::point_constraint>(registry, bodyA, bodyB, [](edyn::point_constraint &point_constraint) {
    // Set pivots.
    point_constraint.pivot[0] = {0, 0.5, 0};
    point_constraint.pivot[1] = {0, -0.5, 0};
});

Do not create edyn::contact_constraint manually, since that is done in the broad-phase collision detection when the AABB of a pair of rigid bodies intersect.

Point constraint

The edyn::point_constraint constrains a point in one rigid body to another point in another rigid body, i.e. it applies impulses to keep both points at the same location in space. It is also known as a point-to-point constraint, or a ball joint.

The pivot points must be assigned to the edyn::point_constraint::pivot array, in the object space of the respective rigid body.

If edyn::point_constraint::friction_torque is non zero, a torque will be applied against the angular velocity of the rigid bodies which will slow them down, preventing them from swinging forever.

Hinge constraint

The edyn::hinge_constraint constrains a pair of rigid bodies to have a pivot point match in space and only allows rotation to happen along a specified axis. It can be used to simulate doors, wheel bearings, elbows, knees, etc.

The edyn::hinge_constraint::pivot array contains the pivot points in the object space of the respective rigid body. That is the location the hinge axis passes through.

The edyn::hinge_constraint::frame property holds an orthonormal basis in the object space of each respective rigid body which represents the orientation of the hinge axis. The first axis in the basis (i.e. the first column in the 3x3 matrix) is the hinge axis. The other two are used to calculate the relative rotation about the hinge axis, which is necessary when using angular limits. The function edyn::hinge_constraint::set_axes provides a quick and simple way to assign the hinge axis.

The edyn::hinge_constraint::angle_min and edyn::hinge_constraint::angle_max hold the angular limits, where angle_min must be smaller than angle_max. The angle between the second or third basis vector of the frames is used to determine the limits. That means you need to know in which direction these basis vectors point towards in order to determine what the limits should be.

The edyn::hinge_constraint::limit_restitution is a restitution coefficient to be used when the limit constraint is activated. When non-zero and the hinge reaches its limit, the rigid bodies will bounce. Must be in [0, 1].

If edyn::hinge_constraint::friction_torque is non zero, a torque will be applied along the hinge axis which will slow down the relative angular velocity of the rigid bodies.

Damping can be used as a form of speed-dependent friction. The edyn::hinge_constraint::damping variable holds the hinge damping in Nm/(rad/s), i.e. torque applied per unit of angular velocity along the hinge axis.

Bump stops can be used to make the limits feel smoother, as if there was a piece of rubber at the limit to make it less harsh. When the distance between the angle and the limit gets below edyn::hinge_constraint::bump_stop_angle, the bump top spring becomes effective with stiffness given by edyn::hinge_constraint::bump_stop_stiffness in Nm/rad.

Hinges can be configured to have a preferred resting angle, which simulates the presence of a spring which forces the hinge to maintain a certain relative angle, within the limits of its strength. The edyn::hinge_constraint::rest_angle holds the relative angle and edyn::hinge_constraint::stiffness holds the spring stiffness in Nm/rad.

Step callbacks

The number of physics steps executed in a call to edyn::update depends on the time it took between subsequent invocations. It might be desirable to run logic before and/or after each physics step, instead of before/after the call to edyn::update. Pre and post step callbacks make it possible. A step callback is a function that takes a registry as argument and can be registered using edyn::set_pre_step_callback and edyn::set_post_step_callback.

In asynchronous execution mode, these callbacks are invoked in the simulation worker in a background thread, which means the registry they receive as argument is not the main registry. Common sense multithreading precautions must be taken.

Asynchronous execution

When Edyn is initialized in asynchronous mode, there are extra details that must be considered. A simulation worker runs in the background and performs the bulk of the work, allowing the main thread to focus on other things.

Modifying components

It's necessary to ensure that changes to components in the main registry are made visible to Edyn when running in asynchronous mode, because these changes must be propagated to the simulation worker. The correct way to do so is via the entt::registry::replace and entt::registry::patch functions, which trigger the invocation of component update observers. If a value is assigned directly to a component reference or pointer, entt::registry::patch must be called without the second argument func.

External components

To propagate changes from the main registry to the simulation worker, Edyn must know which components must be replicated. Among Edyn's own components, it knows which must be replicated, but it's impossible to decipher which of your components must also be replicated. For that reason, these external components must be registered.

struct ext_component {};
// Make Edyn aware of external component.
edyn::register_external_components<ext_component>(registry);
// Now the external components will be available in the simulation worker
// and in the pre/post step callback.

The entities in the simulation worker's registry do not match up with the entities in the main registry, since in EnTT there's no possibility of creating an entity with a specific value. Thus, entity mapping is done, i.e. for every new entity in the main registry, a corresponding new entity is created in the simulation worker's registry and a bidirectional map is established. For that reason, components that contain entt::entity values need to be transformed into simulation worker's space when imported, and vice-versa. If your external component has an entt::entity in it, it has to be registered with EnTT's runtime reflection system entt::meta and at the very least, all members that contain entities (be it a plain entt::entity or a container of entities such as std::vector<entt::entity>) must be specified. Edyn will search through the members registered in entt::meta to find which ones contain entities and map them from remote to local.

struct ext_component {
    entt::entity entity;
};

// Register external component later.
edyn::register_external_components<ext_component>(registry);
// Register component with entt::meta.
entt::meta<ext_component>().type().data<&ext_component::entity, entt::as_ref_t>("entity"_hs);

Now, when components of this type are imported into the simulation worker's registry, it will point to the correct entity.

Besides mapping foreign entities into the local registry, it might be desirable to perform other transformations in a component when it's imported. An override or specialization of the function template edyn::merge_component can be provided to replace the default behavior, which simply assigns the remote value. For example, if your component contains a std::vector and you want to append new elements into it instead of replacing, an implementation such as this can be used:

template<>
void edyn::merge_component<MyComponent>(MyComponent &current, const MyComponent &new_value) {
    current.vec.insert(current.vec.end(), new_value.vec.begin(), new_value.vec.end());
}

External entities

It might be necessary to have an entity which is not a rigid body to be present in the simulation worker so it will be available in a step callback. That can be achieved by tagging it as an external entity using edyn::tag_external_entity and connecting it to a rigid body using a edyn::null_constraint. Tagging it as external, causes a node to be inserted into the entity graph for that entity and the null constraint creates an edge in the entity graph connecting the external entity to the rigid body. Now this entity and its components will be replicated in the simulation worker.

auto rb = edyn::make_rigidbody(registry, def);
auto external = registry.create();
edyn::tag_external_entity(registry, external);
edyn::make_constraint<edyn::null_constraint>(registry, rb, external);

Collision filtering

Collisions can be filtered using collision groups and masks, which are a pair of 64-bit unsigned ints used a bitsets. Each bit represents one group and high bit signals presence in that group. A high bit in the mask bitset indicates participation in collisions with bodies in the group in that same bit position. For example, if one rigid body has a collision group of 1 and another has a collision mask of ~1 (bitwise not) then they will not collide.

The collision group and mask can be set in the rigid body definition:

auto def1 = edyn::rigidbody_def();
//...
def1.collision_group = 1ull; // This rigid body is in the first group...
def1.collision_mask = ~(1ull << 1); // ...and it does not collide with rigid bodies in the second group.
//...
edyn::make_rigidbody(registry, def1);
// Make a rigid body which does not collide with the one created above.
auto def2 = edyn::rigidbody_def();
//...
def2.collision_group = (1ull << 1); // This rigid body is in the second group...
def2.collision_mask = ~1ull; // ...and it does not collide with rigid bodies in the first group.
//...
edyn::make_rigidbody(registry, def2);

The edyn::collision_filter component holds that information, which can be updated at any time.

Collision exclusion lists can be used for fine grained collision filtering. The list of entities a rigid body should not collide with is stored in a edyn::collision_exclusion component. Call edyn::exclude_collision to add a collision exclusion pair.

The collision filtering logic can be overridden by replacing the should_collide function, which can be done calling edyn::set_should_collide. It takes a const registry and two entities as parameters and returns a boolean. If the default behavior is desired as part of the new logic, edyn::should_collide_default can be called directly.

Observing collision events

Collision events can be observed using the following sinks:

  • edyn::on_contact_started: Triggered when a contact starts, i.e. when the first contact point is added to a manifold.
  • edyn::on_contact_ended: Triggered when a contact ends, i.e. when the number of points in a manifold goes to zero.
  • edyn::on_contact_point_created: Triggered when a contact point is created. The signal emits the manifold entity and the contact point id in that manifold.
  • edyn::on_contact_point_destroyed: Triggered when a contact point is destroyed. The signal emits the manifold entity and the contact point id in that manifold.

An example:

void contact_started(entt::registry &registry, entt::entity entity) {
    auto &manifold = registry.get<edyn::contact_manifold>(entity);
    float normal_impulse = 0;

    for (unsigned i = 0; i < manifold.num_points; ++i) {
        auto &cp = manifold.point[manifold.ids[i]];
        normal_impulse += cp.normal_impulse + cp.normal_restitution_impulse;
    }

    // Do something with `normal_impulse`, e.g. play sound.
}

/// ...

// Pass `registry` to the call to `connect` so it will be stored and passed as
// a context variable in the invocation to `contact_started`. See EnTT documentation
// on signals for details.
edyn::on_contact_started(registry).connect<&contact_started>(registry);

You can find an example of how to use collision events to play sounds in the billiards sample in Edyn Testbed.

The contact_manifold uses a list of indices in the ids array to the indices of active contact points in the points array. That keeps contact points in a stable location in the array and allows them to be referred to by a stable id/index. That is also used as a small optimization so contact points don't have to be moved within the array on deletion (which is done by swapping with the last element in the ids array) which would be a little more expensive since edyn::contact_point is a rather big struct.

The normal and friction impulses generated by collisions with restitution are stored separately in edyn::contact_point::normal_restitution_impulse and edyn::contact_point::friction_restitution_impulse if the number of restitution iterations is non-zero (i.e. the restitution solver is being used) because because if mixed with normal_impulse and friction_impulse the constraint solver will remove some of the propagated shock and the results will not be correct. Add them up to get the full normal and friction impulses.

Two constraints are used to produce friction, each applying impulses in two orthogonal directions tangent to the surface, thus both being orthogonal to the contact normal as well. These directions are not cached but since they're calculated using edyn::plane_space, they can be obtained using the same function and passing the contact normal as argument.

void contact_started(entt::registry &registry, entt::entity entity) {
    // Assume there is at least one contact point.
    auto &cp = manifold.point[manifold.ids[0]];
    auto normal_impulse = cp.normal_impulse;
    auto friction_impulse0 = cp.friction_impulse[0];
    auto friction_impulse1 = cp.friction_impulse[1];
    // Obtain friction directions.
    edyn::vector3 tangent[2];
    edyn::plane_space(cp.normal, tangent[0], tangent[1]);
    // Since the friction impulses are the components of two orthogonal directions,
    // the total friction impulse magnitude is the length of a 2D vector with the
    // impulses as coordinates.
    auto total_friction_impulse = edyn::length(edyn::vector2{friction_impulse0, friction_impulse1});
    // Do something with the impulses...
}

edyn::on_contact_started(registry).connect<&contact_started>(registry);

Materials

The rigid body's material hold surface properties such as friction and restitution. Individual base properties are assigned to the material of each rigid body and when they collide, these properties must be combined into one for the collision response. Default functions exist for the combination of these values in material_mixing.hpp but it might be desirable to provide specific values for certain pairs of materials. A numerical id can be assigned to materials and then their combined properties can be specified via edyn::insert_material_mixing, which takes as arguments a pair of material ids and the desired material properties for that combination. When two bodies collide, the combined material properties will be used, otherwise the base property values will be mixed according to the default mixing functions.

// Specifying material properties for a pair of materials.
auto ball_mat_id = 0;
auto table_mat_id = 1;
// Material for ball-ball collision.
auto ball_ball_mat = edyn::material_base{};
ball_ball_mat.friction = 0.05;
ball_ball_mat.restitution = 0.95;
edyn::insert_material_mixing(registry, ball_mat_id, ball_mat_id, ball_ball_mat);
// Material for ball-table collision.
auto table_ball_mat = edyn::material_base{};
table_ball_mat.friction = 0.2;
table_ball_mat.restitution = 0.5;
edyn::insert_material_mixing(registry, ball_mat_id, table_mat_id, table_ball_mat);

// Then, assign the material id in the rigidbody def.
auto table_def = edyn::rigidbody_def();
table_def.material->id = table_mat_id;
// Assign properties to be mixed with other materials for which there isn't an
// entry in the material mixing table.
table_def.material->restitution = 0.5;
table_def.material->friction = 0.2;
// ...
edyn::make_rigidbody(registry, table_def);

Friction

As mentioned earlier, sliding friction is solved using two orthogonal directions which are tangent to the contact surface.

Spinning friction applies torque along the contact normal. It generally only makes sense in spherical shapes.

Rolling friction works similarly to sliding friction, where it uses the same orthogonal tangential vectors to apply torque and remove angular velocity from the rolling bodies. Rolling friction is only applied to shapes that can roll, such as spheres, capsules and cylinders. For cylinders specifically, it is only applied along the cylinder's main axis. In the literature, the coefficient of rolling resistance often represents the magnitude of force that's applied at the center of mass in the opposite direction of motion of a rolling body per unit of weight, whereas in Edyn, the coefficient at edyn::material::roll_friction represents an amount of torque that is applied per unit of weight. Thus, a real world coefficient of rolling resistance should be multiplied by the radius of the rolling shape before assigning it to the material.

Restitution

The coefficient of restitution represents the elasticity or bounciness of a rigid body. To properly propagate the shock of a collision on a chain of connected rigid bodies with non-zero restitution, Edyn employs a restitution solver which runs before the constraint solver. The restitution solver solves small groups of contact constraints in isolation over a few iterations until the normal relative velocity of all contact points is positive, i.e. they're separating (within a threshold).

The number of iterations can be set via edyn::set_solver_restitution_iterations and edyn::set_solver_individual_restitution_iterations, where the latter represents the number of iterations used when solving each subgroup of constraints. If the number of iterations is set to zero, the restitution solver is deactivated. Restitution will still work in this case, though in limited fashion, where only the contacts with non-zero restitution which have an initial penetration velocity will actually be treated as having non-zero restitution and existing contacts which have zero normal relative velocity will be treated as if their restitution was zero, which is a limitation of the sequential impulses constraint solver. The restitution solver can be quite expensive to run so you might want to deactivate it if you don't need this effect.

Per-vertex material properties

It is possible to have per-vertex friction and restitution coefficients in triangle meshes (edyn::mesh_shape and edyn::paged_mesh_shape). For edyn::mesh_shape, the functions edyn::triangle_mesh::insert_friction_coefficients and edyn::triangle_mesh::insert_restitution_coefficients can be used to assign the coefficients to the triangle mesh.

The function edyn::load_tri_mesh_from_obj can load vertex colors which can be passed to edyn::create_paged_triangle_mesh which will assign the material properties from the vertex colors when creating the edyn::paged_triangle_mesh. The red color is interpreted as friction, the green color as restitution. The vertex colors can be separated and passed to edyn::triangle_mesh::insert_friction_coefficients and edyn::triangle_mesh::insert_restitution_coefficients (see example).

Note that the .obj file format does not officially support vertex colors. Unofficial extensions exist where the vertex color is included right after the 3 vertex coordinates in a v declaration, such as v 7.75 7.75 0.0 1.0 0.0 0.0, in which case the RGB color would be (255, 0, 0), i.e. red. Blender does not write nor read vertex colors to and from an .obj file, though it is possible to export the mesh in the .ply format, which includes vertex colors, and then import it in MeshLab and export an .obj file with vertex colors.

The material properties are interpolated among the vertices of the triangle which contains the contact point and then mixed with the material of the dynamic rigid body. Note that a material mixing pair will override the per-vertex material.

Shifting the center of mass

By default, the center of mass is the centroid of a shape. The center of mass can be specified in the edyn::rigidbody_def and it can also be changed later using edyn::set_center_of_mass. The center of mass is specified as edyn::vector3 which is an offset from the centroid in object space. The moment of inertia about the new center of mass can be calculated using the parallel axis theorem by calling edyn::shift_moment_of_inertia.

auto def = edyn::rigidbody_def();
def.mass = 100;
def.shape = edyn::box_shape{0.2, 0.2, 0.2};
def.center_of_mass = {0.1, 0.1, 0.1};
auto entity = edyn::make_rigidbody(registry, def);

// It can also be changed dynamically later.
edyn::set_center_of_mass(registry, entity, {0.05, -0.1, 0});

It is important to note that edyn::position represents the position of the center of mass and edyn::linvel represents the velocity of the center of mass. For that reason, whenever the center of mass is changed, those values are updated to reflect the state at the new center of mass. edyn::get_rigidbody_origin can be used to get the position of the origin in world space (the origin is always zero in object space).

All constraint pivots are relative to the origin. That includes contact points. Thus it is important to remember to use the position of the rigid body origin when converting these pivots into world space, and not the edyn::position (unless the center of mass offset is zero, of course). This makes it possible to change the center of mass dynamically without having to modify the pivots of all constraints that connect to a rigid body.

Changing shapes during run time

The properties of the current shape of a rigid body can be changed directly without any extra steps and the effects will be immediately applied into the simulation. It's just important to remember that in asynchronous mode either the entt::registry::replace or entt::registry::patch functions must be called to propagate changes to the simulation worker.

To assign a shape of a different type or clear the current shape to turn a rigid body amorphous, the edyn::rigidbody_set_shape function must be called. It takes an std::optional<edyn::shapes_variant_t> which can contain any of the supported shapes or could be empty to make the rigid body amorphous.

Closest point calculation

The collision detection APIs can be used independently. The edyn::collide function is overloaded for every pair of shape type and it calculates the closest points between them.

// Calculate closest points between two boxes.
auto box = edyn::box_shape{edyn::vector3{0.5, 0.5, 0.5}};
auto ctx = edyn::collision_context{};
ctx.posA = edyn::vector3{0,0,0};
ctx.ornA = edyn::quaternion_identity;
ctx.posB = edyn::vector3{0, 2 * box.half_extents.y, 0};
ctx.ornB = edyn::quaternion_identity;
// If the shapes are farther away than `ctx.threshold`, no contact points will be generated.
ctx.threshold = 0.2;
auto result = edyn::collision_result{};
edyn::collide(box, box, ctx, result);
// `result` now contains the closest points.

// Since both shapes are boxes, the `result` also contains the closest features,
// which enables logic to be written based on which specific feature are the closest.
if (result.num_points > 0) {
    auto &point = result.point[0];
    auto featureA = std::get<edyn::box_feature>(point.featureA->feature);
    if (featureA == edyn::box_feature::face && point.featureA->index == 2) {
        // Do something specific when the face #2 (upper face, i.e. Y+) of box A is the closest feature...
    }
}

Each point in the result, which is of type edyn::collision_result::collision_point, contains the closest points in object space (pivotA and pivotB) the contact normal and the signed distance.

It may also contain the closest features (featureA and featureB). The feature will not be present for shapes which don't have any (such as sphere and plane) and for shapes where it would require extra calculations to obtain them (such as polyhedron shape). Since the closest features are not necessary for the physics engine to function in most cases, it has been chosen to only provide them if they're already available as a result of the closest point calculation. The only exception where they are needed in the physics engine, is when per-vertex materials are being used in a triangle mesh, where it needs to know which triangle is involved in the collision in order to interpolate the values at the vertices.

Ray-casting

In sequential execution mode, ray-casting can be done using the edyn::raycast function, such as:

// Given points `p0` and `p1` for the ray:
auto result = edyn::raycast(registry, p0, p1);

if (result.entity != entt::null) {
    // Calculate point of intersection.
    auto intersection = edyn::lerp(p0, p1, result.fraction);
    // Access extra info.
    if (registry.any_of<edyn::box_shape>(result.entity)) {
        // Since the hit entity has a `box_shape`, it means the info is a `box_raycast_info`.
        auto info = std::get<edyn::box_raycast_info>(result.info_var);
        // Get the index of the face that was hit...
        auto face_idx = info.face_index;
        // ...then do something with it...
    }
}

In asynchronous execution mode, the edyn::raycast_async function must be used, such as:

void process_raycast_result(edyn::raycast_id_type id, const edyn::raycast_result &result,
                            edyn::vector3 p0, edyn::vector3 p1) {
    // Calculate point of intersection.
    auto intersection = edyn::lerp(p0, p1, result.fraction);
    // Access extra info.
    if (registry.any_of<edyn::box_shape>(result.entity)) {
        // Since the hit entity has a `box_shape`, it means the info is a `box_raycast_info`.
        auto info = std::get<edyn::box_raycast_info>(result.info_var);
        // Get the index of the face that was hit...
        auto face_idx = info.face_index;
        // ...then do something with it...
    }
}

// The delegate will be invoked when the result is sent back from the simulation worker.
auto delegate = entt::delegate(entt::connect_arg_t<&process_raycast_result>{});
edyn::raycast_async(registry, p0, p1, delegate);

In a pre/post step callback, the former edyn::raycast must be used, independent of the execution mode. It's just important to remember that in the asynchronous case, the callback is running in a background thread and operating on the simulation worker's registry.

The result contains the entity that was hit first by the ray, or it may be entt::null if nothing was hit. It also contains the fraction between p0 and p1 where the intersection occurs, which allows the intersection point to be calculated using linear interpolation. It also contains the normal vector at the point of intersection and extra info in the info_var member. The contents of the variant info_var depends on the type of shape that was hit. It is empty for a edyn::sphere_shape since there's no extra information for a sphere intersection, or in case a edyn::polyhedron_shape is hit, it has a edyn::polyhedron_raycast_info which contains the index of the face that was hit.

Angles

All angles in Edyn are specified in radians. The utility functions edyn::to_radians and edyn::to_degrees can be used to convert between radians and degrees and vice-versa.

Torque is specified in Nm/rad, which is a practical unit for the engine internals due to radians being used everywhere, but it is not an intuitive unit of measurement. The edyn::to_Nm_per_radian function will convert from Nm/degree to Nm/rad.

Rag dolls

Rag dolls can be created with a set of rigid bodies constrained by hinge, CV-joint and cone constraints. Knees and elbows can be modeled with a hinge, while shoulders, wrists, hips, spine, neck and ankles need a CV-joint and a cone constraint. Each rigid body and constraint must be carefully measured and positioned and constraint limits must be set, which makes assembling rag dolls quite complicated. Edyn offers a rag doll construction utility which can make generic rag dolls with few parameters.

auto rag_def = edyn::ragdoll_simple_def{};
rag_def.height = 1.8;
rag_def.weight = 82;
rag_def.position = {2, 3, -1};
rag_def.orientation = edyn::quaternion_axis_angle({0, 0, 1}, edyn::to_radians(26));
rag_def.friction = 0.6;
rag_def.restitution = 0.2;
auto entities = edyn::make_ragdoll(registry, rag_def);

The returned edyn::ragdoll_entities contains the entities for all rigid bodies and constraints that have been created for the rag doll, thus allowing extra fine tuning of constraint limits for example. The transform of these rigid bodies can be used to drive the bones of a skinned mesh. It's important that the pivots and lengths of the bones match that of the rigid bodies, which means that it's going to be necessary to manually input sizes in a edyn::ragdoll_def (e.g. edyn::ragdoll_def::arm_upper_size::x for the upper arm length). To make it more approachable, a full rag doll definition can be created from a simple using edyn::make_ragdoll_def_from_simple and then the values can be edited.

The edyn::ragdoll_entities contains separate entities for several body parts. Notable ones are the shoulder and the arm twist entities. A separate rigid body is created for the shoulder, which simulates movement of the scapula and collar bone. It is an amorphous rigid body (i.e. it doesn't have a shape). It is connected to the upper torso and the upper arm connects to it. The arm twist rigid body is also amorphous and it simulates twisting of the forearm. It is connected via a hinge to the lower arm body and the hand connects to it.

The complexity of a rag doll can lead to unstable simulations at the default simulation rate of 60 steps per second. It might be necessary to increase it by using a lower fixed delta time such as 4 or 8 milliseconds, which can be set via edyn::set_fixed_dt.

Networked physics

Edyn supports network synchronization in a client-server architecture. It implements a jitter buffer (aka playout delay buffer) in the server-side and performs extrapolation in the client-side. It writes the state of physical entities into packets which are provided via an EnTT signal and received packets must be fed into the engine. How the packet data is transmitted between clients and server is up to the user, who can use their means of choice.

Entities that must be shared across the network must have a edyn::networked_tag assigned to them. This includes rigid bodies, constraints and external entities.

Registry snapshots

Client and server exchange registry snapshots with each other which contain a set of entities and components to be imported into their registries. Snapshots are sent regularly many times per second (between 10 and 30 times per second, usually) and will only include components that have changed recently. It will often include rigid body transforms and velocities, as these change all the time.

These snapshots operate on the assumption that packet loss will happen, thus they can be sent through an unreliable channel via UDP. To decrease the chances that the latest state of a component won't be delivered, when a networked component changes, it will be included repeatedly in the next few packets.

The snapshot rate can be set using edyn::set_network_client_snapshot_rate in the client. In the server, it is assigned to each client in the edyn::remote_client component.

AABB of interest

Every client has an AABB of interest in the server, which determines which entities will be sent to the client. As entities come in and out of the AABB, they will be consequently instantiated and destroyed in the client.

Server

The server is initialized with a call to edyn::init_network_server and it's necessary to register with the packet sink edyn::network_server_packet_sink so packets can be sent over the network when they're generated. The sink function could look like:

void send_edyn_packet_to_client(entt::registry &registry,
                                entt::entity client_entity,
                                const edyn::packet::edyn_packet &packet)
{
    auto data = std::vector<uint8_t>{};
    auto archive = edyn::memory_output_archive(data);
    archive(packet);

    // Then send `data` over the network...
}

When new clients connect to the server, a client must be created using edyn::server_make_client. All client properties are assigned to the client entity and any application-specific properties should be assigned as well. When the client disconnects, the client entity should be destroyed.

A real application will often have its own list of packet types, and the edyn::edyn_packet must become one of them. When an edyn_packet is received, it must be deserialized and fed into the engine, using edyn::server_receive_packet, such as:

auto archive = edyn::memory_input_archive(data, data_length);
edyn::packet::edyn_packet packet;
archive(packet);

if (!archive.failed()) {
    // client_entity is the entity of the client who sent this packet.
    edyn::server_receive_packet(registry, client_entity, packet);
}

The edyn::update_network_server function must be called regularly before edyn::update to perform the server duties, such as processing packets, updating AABBs of interest and publishing registry snapshots.

For more details, see edyn_server.cpp for an example of a server setup using ENet.

Client

A client must be initialized with a call to edyn::init_network_client. When the client connects to a server, edyn::network_client_packet_sink must be called to register a listener which will dispatch the edyn_packets to server as they're generated. The listener could look like:

void send_edyn_packet_to_server(const edyn::packet::edyn_packet &packet)
{
    auto data = std::vector<uint8_t>{};
    auto archive = edyn::memory_output_archive(data);
    archive(packet);

    // Then send `data` over the network...
}

When an edyn_packet arrives, it must be fed into the engine using edyn::client_receive_packet, such as:

auto archive = edyn::memory_input_archive(data, data_length);
edyn::packet::edyn_packet packet;
archive(packet);

if (!archive.failed()) {
    edyn::client_receive_packet(registry, packet);
}

The edyn::update_network_client function must be called regularly, before edyn::update, to perform the client-side duties, such as processing created and destroyed networked entities, publishing registry snapshots, and starting extrapolation jobs and merging their results into the simulation.

For more details, see basic_networking.cpp for an example of a client setup using ENet.

Assets

When entities enter the AABB of interest of a client, the server will package all of their components into a edyn::packet::create_entity packet and send it to the client which will be able to instantiate the same entities with all their components (note that all entities in the island are included). A problem with this standard behavior is that often, entities belong to a group which has particular information associated with it, and a lot of this information is static, and could be quite large. An example would be a polyhedron shape. Other information would be graphical elements and sounds that must be loaded along with the physics asset. This information could be available locally and not have to be transferred by the game server, which should instead focus on the real-time interaction among players.

Using asset references, it is possible to declare and asset and insert networked entities into it to form a group that will be instantiated in the other end with minimal effort by the game server. When an entity that belongs to an asset enters the AABB of interest, the client will be notified that an entity of an asset with a certain ID entered the zone. With the asset ID, the client can obtain the asset, instantiate it and link the local entities to server entities via the common internal entity IDs contained in the asset which are globally unique.

To instantiate an asset in the server, first create the rigid bodies, constraints and external entities and their components as usual, and then create an asset entity with an edyn::asset_ref component which contains the unique asset ID. Then for every entity that should be networked, use edyn::assign_to_asset to insert it into the asset and declare which components should be synchronized on instantiation.

The client should subscribe to the edyn::network_client_entity_entered_sink to be notified of asset entities that entered its AABB of interest. Using the asset ID present in the replicated edyn::asset_ref, the client can obtain the asset from file, from cache or download it from a data server. If the asset is available immediately, it should be instantiated and then linked using edyn::client_link_asset, which will do the job of linking local and remote entities. If the asset needs to be loaded asynchronously, do not call edyn::client_link_asset just yet. Instead, call edyn::client_asset_ready when the asset has finished loading and is ready to be instantiated. This call will request the state of relevant components first so the asset can be instantiated in the correct initial state. The client should subscribe to edyn::network_client_instantiate_asset_sink which will be triggered when the initial state arrives and the asset can be instantiated there.

See the vehicle networking example in Edyn Testbed for a complete implementation.

Discontinuities

When extrapolated state is merged into the current simulation, discontinuities are created due to misprediction. These discontinuities are accumulated each time an extrapolation finishes and their value is added to the current transform and assigned to the present transforms (edyn::present_position and edyn::present_orientation). Then, they are decayed over time, thus smoothing out what would be jittery motion. The rate with which they decay can be set using edyn::set_network_client_discontinuity_decay_rate, which is a value in [0, 1) that multiplies the current discontinuity offset and assigns the result to itself in every step of the simulation. Changes to the fixed delta time will have the undesirable effect of changing the rate of decay.

Round-trip time

The round-trip time (RTT) is an important value for internal timing calculations and it is usually available in networking engines. It must be updated regularly using edyn::set_network_client_round_trip_time in the client-side, and edyn::server_set_client_round_trip_time for each client in the server-side.

Packet reliability

Ideally, communication will be done via UDP with a custom reliability layer on top, such as what ENet and Yojimbo do. Packet loss is acceptable for certain packets, such as registry snapshots, which are sent many times per second. The function edyn::should_send_reliably will tell whether the packet needs reliability, which is information that can be passed into the networking library to allow it to operate more efficiently by not checking for packet loss and not resending the packets that are sent most often.

External networked components

External components can be registered with Edyn to be included in the registry snapshot packets. They must be registered as external components using edyn::register_external_components, and then registered as networked components using edyn::register_networked_components. Edyn needs to know how to read and write the external component into a packet, thus a serialization function must be provided. If the component is an empty type, writing a serialization function is not necessary. The serialization function must be written with the form:

template<typename Archive>
void serialize(Archive &archive, MyComponent &comp) {
    archive(comp.member_one);
    archive(comp.member_two);
    // etc
}

This function will be called when de/serializing registry snapshot packets.

Inputs

Components can be tagged as input by deriving from edyn::network_input which turns them into components that are fully owned by the client and the server will always accept their state, as long as they don't fail data validation. Components that are user input (e.g. steering of a vehicle) should be tagged as such.

Whenever an input component changes, it will be included in the next few snapshots to decrease chances of the data not reaching the server since packet loss is possible. This means only idempotent inputs can be shared in this form, because they will be received at the other end multiple times and changes that happen in between snapshots will no be captured, meaning that a slight amount of data loss wouldn't affect the behavior of the simulation much.

For inputs that are not idempotent, actions can be used instead. Actions are one-shot events that must be evaluated and then discarded, and can be registered separately in the call to edyn::register_external_components and edyn::register_networked_components (they must be specified in both). It's important to note that actions are not components. Instead, they are accumulated in edyn::action_lists and consumed at the end of each update. The edyn::action_lists are sent to the simulation worker and then processed in a step callback. They're also deleted afterwards. To add actions, simply emplace or get the current edyn::action_list<Action> for that entity and add it to its list.

At the end of each update, before clearing all action lists, they're added to an action history which holds a timestamped list of the most recent actions. The history is included in every registry snapshot, meaning that even if one snapshot is lost, the following one will contain the actions that happened at that point in time, thus decreasing the probability of an action not reaching the server.

It's also necessary to write serialization functions for every action that is not an empty type.