25. OpenPLX for AGX Dynamics

OpenPLX is a high-level modeling language designed to work seamlessly with AGX Dynamics. It provides a structured approach to defining physics simulations, allowing users to create and configure rigid bodies, constraints, motors, friction models, and more in a human-readable format.

By leveraging AGX Dynamics, OpenPLX enables the simulation of complex mechanical systems, vehicles, robotics, and deformable terrains with minimal effort.

Note

OpenPLX is a work in progress. This draft version will evolve with user feedback and experience. We welcome your input and collaboration.

This page explains how OpenPLX interacts with AGX Dynamics and provides a structured way to define physics simulations. For a complete overview of OpenPLX Syntax and Bundles, consult the OpenPLX Documentation.

Note

This version of AGX (2.41.0.0) is built with OpenPLX version 0.20.1. OpenPLX release log.

25.1. How OpenPLX Works with AGX Dynamics

OpenPLX acts as an interface layer for AGX Dynamics, converting structured OpenPLX definitions into AGX simulation components. When you load an OpenPLX file, it is transformed into an AGX Dynamics simulation tree, allowing for efficient physics-based interactions.

This means:

  1. OpenPLX describes the physics setup and the scene.

  2. The AGX Dynamics engine executes the simulation.

  3. Users can interact with the scene through OpenPLX files.

  4. Python controllers interact by sending or receiving OpenPLX signals.

25.2. Simulating an OpenPLX File in AGX Viewer

To simulate an .openplx file with AGX Dynamics, pass it to agxViewer like you would with an .agx file:

agxViewer myModel.openplx

25.3. Importing an AGX File in OpenPLX

AGX .agx files contain pre-defined physics models. OpenPLX supports seamless integration of AGX models into simulation systems.

  1. The AGX Model describes the basic physics setup, including rigid bodies, constraints, collision geometries and visuals.

  2. OpenPLX imports the AGX model and augments it with additional components, such as tracks and a drivetrain.

  3. OpenPLX describes the complete simulation scene.

  4. Controller scripts (python/C++) connects the OpenPLX model to the desired control systems.

  5. The AGX Dynamics engine executes the simulation.

25.3.1. Syntax for Importing an AGX File

To import an .agx file into OpenPLX, use the following OpenPLX syntax:

import @"model.agx" as AGXModel

Scene is Physics3D.System:
  my_model is AGXModel

The imported AGX model (AGXModel) can now be referenced within OpenPLX.

To load the OpenPLX scene and view the AGX model, use:

agxViewer scene.openplx -p

25.3.2. Viewing an AGX File as an OpenPLX Model

You can open an AGX file to find the components you need to reference using the anytoopenplx command:

python -m agxPythonModules.openplx.anytoopenplx model.agx > model_reference.openplx

Use this file to identify signals and components to reference when augmenting your model with additional OpenPLX components.

Note

At the moment, the models generated OpenPLX file will duplicate the content of the agx file, creating a conflict when running the simulation. To accomodate this, change the file extension of the new .openplx file to .txt, or place it outside the root folder of your OpenPLX bundle.

25.4. OpenPLX Tutorials

Explore the OpenPLX Tutorials to get started with OpenPLX for AGX Dynamics.

25.5. AGX Annotations

Table 25.1 AGX Parameters

Annotation

Description

Type

agx_relaxation_time

Directly set the AGX Dampling.
Applies to: Physics3D.Interactions.Mate

Real

agx_solve_type

Set the AGX Solve type for a constraint.
Applies to Physics3D.Interactions.Mate
Accepted values "DIRECT" | "DIRECT_AND_ITERATIVE" | "ITERATIVE"

String

agx_friction_solve_type

Sets the AGX Solve type for the fricion model.
Applies to Physics.Interactions.Dissipation.DefaultDissipation
Accepted values "SPLIT" | "DIRECT" | "DIRECT_AND_ITERATIVE" | "ITERATIVE"

String

agx_approximate_cone_friction

Enables AGX approximate cone friction.

Bool

agx_terrain_material

Sets an AGX terrain material preset.
Applies to Terrain.TerrainMaterial

String

agx_actuator_internal_inertia

Sets the internal inertia of the input shaft of a agxPowerLine::RotationalActuator or the internal mass of the input rod of a agxPowerLine::TranslationalActuator.
Applies to DriveTrain.HingeActuator and DriveTrain.PrismaticActuator

Real

agx_observer_frame

Maps a Physics3D.Interactions.MateConnector to a agx::ObserverFrame.
Applies to Physics3D.Interactions.MateConnector

Bool

agx_debug_render_frame

Renders the axes of a Physics3D.Interactions.MateConnector, also maps it to a agx::ObserverFrame.
Applies to Physics3D.Interactions.MateConnector

Bool

25.6. AGX Track Annotations

The following annotations can be applied to a Vehicles.Tracks.System to set AGX internal track properties.

Table 25.2 AGX Track Annotations

Annotation

Description

Type

agx_track_node_wheel_overlap

setTransformNodesToWheelsOverlap

Real

agx_track_on_initialize_merge_nodes_to_wheels

setEnableOnInitializeMergeNodesToWheels

Bool

agx_track_on_initialize_transform_nodes_to_wheels

setEnableOnInitializeTransformNodesToWheels

Bool

agx_track_hinge_range_lower, agx_track_hinge_range_upper

setHingeRangeRange

Real

agx_track_hinge_compliance

setHingeCompliance

Real

agx_track_hinge_relaxation_time

setHingeDamping

Real

agx_track_stabilizing_friction_parameter

setStabilizingHingeFrictionParameter

Real

agx_track_min_stabilizing_normal_force

setMinStabilizingHingeNormalForce

Real

agx_track_node_wheel_merge_threshold

setNodesToWheelsMergeThreshold

Real

agx_track_node_wheel_split_threshold

setNodesToWheelsSplitThreshold

Real

agx_track_num_nodes_in_average_direction

setNumNodesIncludedInAverageDirection

Int

agx_set_enable_merge

setEnableMerge

Bool

agx_set_contact_reduction

setContactReduction
Accepts: "NONE" | "MINIMAL" | "MODERATE" | "AGGRESSIVE"

String

agx_set_enable_lock_to_reach_merge_condition

setEnableLockToReachMergeCondition

Bool

agx_set_lock_to_reach_merge_condition_compliance

setLockToReachMergeConditionCompliance

Real

agx_set_lock_to_reach_merge_condition_relaxation_time

setLockToReachMergeConditionDamping

Real

agx_set_num_nodes_per_merge_segment

setNumNodesPerMergeSegment

Int

25.7. AGX Track Wheel Annotations

The following annotations can be applied to a Vehicles.Tracks.RoadWheel to set AGX Track Wheel properties.

Table 25.3 AGX Track Wheel Annotations

Annotation

Description

Type

agx_track_wheel_split_segments

SPLIT_SEGMENTS

Bool

25.8. AGX Plugin Annotations

When importing a .agx file there are a few annotations that change the import behavior.

Table 25.4 AGX Plugin Annotations

Annotation

Description

Type

discard_rigid_body_positions

Discards all position information for rigid bodies if set to true, allowing SNAP to reposition them.

Bool

regenerate_shape_uuids

Setting this to true will create new UUIDs for all AGX shapes. This is useful when importing the same .agx file twice.

Bool

material_naming_rule

Controls how imported materials will be named. This can be necessary to avoid collisions since materials are always put in a global scope.

Accepted values

"UUID" sets the material unique_name to the AGX UUID.

"OPENPLX_NAME" sets the material unique_name to the OpenPLX name.

"AGX_NAME" (default) sets the material unique_name to the AGX name.

If UUIDs are not unique, try "OPENPLX_NAME" together with a namespace to generate unique names.

String

ignore_disabled_secondary_constraints

Secondary constraints that are disabled are not imported if this is set to true. Can improve performance when importing the AGX file.

Bool

26. OpenPLX → AGX: Mapping Guide

26.1. Scope

A guide showing how each OpenPLX types and attributes end up in AGX.

26.2. Core object / ID / transform mapping

OpenPLX

AGX

Notes

Object::getName()

agx::Name

The name of an object in AGX is generally the full OpenPLX name including all namespaces with dot separation.

.uuid

getUuid()

A .uuid: annotation in an OpenPLX object mapped to AGX will enforce that to the created AGX object. If no annotation exist AGX will generate a new uuid.

Math::AffineTransform

agx::AffineMatrix4x4

mapLocalTransform writes the local transform on assemblies, bodies and geometries.

System / Body / Geometry

agxSDK::Assembly / agx::RigidBody / agxCollide::Geometry

The OpenPLX system tree maps to an assembly tree in AGX. Systems include bodies and geometries. Bodies include geometries.

MateConnector

agx::Frame / agx::ObserverFrame

Pose computed from main axis/normal/position; observer frames preserved for AGX-imported connectors.

26.3. Bodies & mass properties

OpenPLX Physics3D::Bodies::RigidBody

AGX agx::RigidBody

Notes

Physics3D::Bodies::RigidBodyKinematics

Kinematics declaration for rigid bodies. Container of velocities and transforms.

Physics3D::Bodies::Inertia

Inertia declaration for rigid bodies. Contains scalar mass and inertia tensor.

is_dynamic is Bool

RigidBody::MotionControl

is_dynamic: True → DYNAMICS; otherwise KINEMATICS.

inertia.mass()

MassProperties::setMass

Negative mass → error. Auto-generate if not given.

inertia.tensor()

MassProperties::setInertiaTensor

CM rotation applied to tensor; SPD validation.

kinematics.local_transform

RigidBody::getFrame()->setLocalMatrix

Local transform relative owning system.

kinematics.local_cm_transform

RigidBody::getCmFrame()->setLocalMatrix

Local CM transform relative the local transform. In AGX the rotation must match model frame. Keep identity rotation!

kinematics.initial_local_linear/angular_velocity

setVelocity / setAngularVelocity

The local OpenPLX velocities will be transformed to world in AGX.

26.4. Geometry (contact shapes & attributes)

OpenPLX

Attributes

AGX mapping

Notes

ContactGeometry

material is Physics::Geometries::Material, local_transform is Math.AffineTransform, enable_collisions is Bool, include_in_mass_properties is Bool

agxCollide::Geometry with one agxCollide::Shape

An OpenPLX ContactGeometry maps to an agx::Geometry with a single shape.

Box

size is Math::Vec3

agxCollide::Box

Size mapped with 0.5 factor per axis for half-extents.

Cylinder

radius is Real, height is Real

agxCollide::Cylinder

The Y axis is the default cylinder axis in AGX.

Capsule(r,h)

radius is Real, height is Real

agxCollide::Capsule

The Y axis is the default capsule axis in AGX.

Sphere

radius is Real

agxCollide::Sphere

ConvexMesh

vertices is Math.Vec3[]

agxCollide::Convex

Built via agxUtil::ConvexReaderWriter.

TriMesh

vertices is Math.Vec3[], indices is Int[]

agxCollide::Trimesh

Built via TrimeshReaderWriter.

ExternalTriMeshGeometry

path is String, scale is Math.Vec3

agxCollide::Trimesh

Path must be absolute; scale → diagonal of Matrix3x3

26.5. Materials & surface contact

OpenPLX

AGX

Notes

Physics::Geometries::Material

agx::Material

Name/UUID; density → BulkMaterial::setDensity.

LinearElasticMaterial

Material::Bulk::setYoungsModulus

A material model that models Young’s modulus.

OpenPLX

Alternatives

AGX mapping

Notes

SurfaceContact.Model

Configurable with attributes listed below.

agx::ContactMaterial

Created/uniqued per material pair in AGX. , tangential_restitution and normal_restitution.

normal_flexibility

LinearElastic, Rigid, PatchElasticity, PointwiseElasticity

stiffness attribute of LinearElastic maps to agx::ContactMaterial::setYoungsModulus

PatchElasticity enables “contact area approach”.

dissipation

MechanicalDamping, ConstraintRelaxationTimeDamping

ContactMaterial::setDamping

ConstraintRelaxationTimeDamping maps directly to Spook damping in AGX. MechanicalDamping = stiffness * Spook damping

friction

DryConeFriction, DryBoxFriction, DryScaleBoxFriction, DryConstantNormalForceFriction, DryDepthScaledConstantNormalForceFriction.

agx::FrictionModel

agx_friction_solve_type & agx_approximate_cone_friction annotations respected; Traits.OrientedFriction in the Physics3D bundle need reference_body/reference_geometry + primary_direction.

clearance

ConstantDistanceClearance and ConstantAngleClearance

ConstantDistanceClearance maps to adhesiveOverlap in SurfaceMaterial::setAdhesion(force, adhesiveOverlap)

Clearance also maps to slack in a SlackHinge, SlackPrismatic.

normal_restitution

A non zero scalar value.

setRestitution

Restitution in the direction of a contact normal.

tangential_restitution

A non zero scalar value.

setTangentialRestitution, OpenPLX value will be set in both primary and secondary direction.

Restitution orthogonal to the contact normal. Not mapped to support a different restitution in the secondary direction.

26.6. Interactions & constraints

An agx::Constraint is created using frames computed from its mate connectors and their respective agx::RigidBody. Each DOF’s compliance and damping (relaxation time) is set from the corresponding OpenPLX flexibility/dissipation component (see section below). Friction controllers on supported constarints are configured from PLX friction.

friction may become DefaultDryFriction, AsymmetricLimitFriction or ConstantLimitFriction. AsymmetricLimitFriction and ConstantLimitFriction will both set agx::FrictionController::setMinimumStaticFrictionForceRange.

Names/UUIDs always propagated.

OpenPLX

Notes on Attributes

AGX mapping

DOFs & extras

Physics3D::Interactions::Hinge

Slack variant if clearance becomes ConstantHingeClearance.

agx::Hinge or agx::SlackHingeJoint

Free to rotate around the main_axis

Physics3D::Interactions::Prismatic

Slack if clearance becomes ConstantPrismaticClearance

agx::Prismatic or agx::SlackPrismaticJoint

Free to move along the main_axis

Physics3D::Interactions::::Cylindrical

agx::CylindricalJoint or agx::SlackCylindricalJoint

Slack variant if clearance becomes ConstantCylindricalClearance

Free to move along and rotate around the main_axis

Physics3D::Interactions::::Ball

No slack version. No mapping of ranges implemented.

agx::BallJoint

Free to rotate around all axes.

Physics3D::Interactions::::Lock

Slack variant if clearance becomes ConstantLockClearance;

agx::LockJoint or agx::SlackLockJoint

Slack if ConstantLockClearance.

Physics3D::Interactions::Distance

No slack version. No mapping of distance range or distance motor implemented.

agx::DistanceJoint

Constrained to keep the distance between the mate connectors, otherwise free to move.

Physics::KinematicLock(bodies)

Add all rigid bodies you like to merge to the bodies array of the KinematicLock.

agx::MergedBody

Bodies merged via agx::MergedBody::EmptyEdgeInteraction.

26.7. Regularization parameters

Most OpenPLX interactions, including mates and surface contact models, have attributes for flexibility and dissipation which will map to compliance and damping in AGX. The OpenPLX models are designed so that if the attributes does not become anything, the parameters will get the default AGX values. The attributes are unique for each mate, listing one parameter for each degree of freedom (DOF). Generally the local axes of a mate use the naming convention of the mate connectors, which are main, normal and cross. Each regularization parameter is defined either around or along one of these axes.

  • flexibility alternatives:

    • Rigidcompliance set to machine-epsilon (nearly rigid).

    • LinearElastic(stiffness)compliance = 1/stiffness. stiffness == 0 → kill DOF (force range 0).

  • dissipation alternatives:

    • ConstraintRelaxationTimeDamping → maps directly to the AGX Spook damping parameter. agx::Constraint::setDamping.

    • MechanicalDamping(damping) which requires flexibility to be LinearElastic(stiffness)spook_damping = damping/stiffness.

26.8. Controllers: motors, ranges, springs (1-DOF controller constraints)

OpenPLX interactions also include springs, motors and ranges. These map to AGX controller constraints. Each controlling one degree of freedom with the possibility to declare regularization parameters.

OpenPLX

AGX

Notes

RotationalVelocityMotor / LinearVelocityMotor

agx::TargetSpeedController via SingleControllerConstraint1DOF

gain > 0compliance = 1/gain; target_speed; enabled flag; force range from min_effort, max_effort; zero_speed_as_spring locks at zero and applies spring flex/dissipation.

TorqueMotor / ForceMotor

Maps to agx::TargetSpeedController in AGX.

Controlled in runtime by updating the force range with required_effort = min = max.

RotationalRange / LinearRange

agx::RangeController

Range [start,end], force range, enable, flexibility and dissipation attributes.

TorsionSpring / LinearSpring

agx::LockController

Position/angle set; force range; enable; flexibility and dissipation attributes.

Annotation agx_imported_controller_constraint

Reuse existing AGX constraint’s motor/range/lock

Present when importing an .agx file, looks up constraint by UUID and attaches controller to the correct DOF.

Annotation agx_solve_type for an OpenPLX Interaction

Constraint::setSolveType

DIRECT / DIRECT_AND_ITERATIVE / ITERATIVE.

26.9. Environment, collisions & signals

OpenPLX

AGX

Notes

Simulation::Environment.gravity

UniformGravityField or PointGravityField

Vector or center+magnitude mapped.

Simulation::CollisionGroup

Geometry/group assignment

Adds all bodies/geometries/systems to AGX groups; respects nested systems.

Simulation::DisableCollisionPair

space->setEnablePair(g1,g2,false)

Applied recursively in disableCollisionPairs.

Physics3D::Signals::MateConnector::Output

ObserverFrame(s)

Ensures frames exist for source and relative connectors (world excluded).

26.10. Friction on constraints (non-contacts)

OpenPLX

AGX

Notes

Interactions::*::friction()

Constraint…::getFrictionController

Dry/limit frictions converted to coefficient or static force ranges; controller disabled if unsupported in PLX side.

26.11. Annotations reference

  • Controller reuse: agx_imported_controller_constraint (UUID of an AGX constraint to attach to).

  • Constraint solve: agx_solve_type (DIRECT, DIRECT_AND_ITERATIVE, ITERATIVE).

  • Friction solve: agx_friction_solve_type (DIRECT, SPLIT, DIRECT_AND_ITERATIVE, ITERATIVE) + agx_approximate_cone_friction (boolean).

  • Oriented friction: reference_body / reference_geometry + primary_direction (Vec3).

  • Terrain material: agx_terrain_material (string).

  • Observer frames: agx_observer_frame_annotation / agx_debug_frame_annotation on MateConnectors.

  • Track-specific: agx_track_*, agx_set_* (see Tracks table).

26.12. Notes on error handling (high-level)

Invalid/duplicate material pairs, bad inertia tensors, negative mass, missing connected bodies, misplaced connectors, invalid OBJ/Trimesh, invalid friction frame, etc., are reported via the provided ErrorReporter and guarded with warnings/fallbacks.