Discover Learn Reference Get OpenPLXSearch Contact

Vehicles bundle

This bundle contains reusable vehicle abstractions for wheels, tracks, chassis, steering, and suspensions.

This tutorial shows how to build an articulated wheel loader by combining:

  • Vehicles.Chassis.Articulated.*
  • Vehicles.Steering.Articulated.*

The examples are written to scale model fidelity up or down:

  • without intermediate link vs with intermediate link
  • DualDistance steering (simpler) vs DualCylinder steering (more detailed)

Step 1: Define reusable frame building blocks

Start with one rigid body and one frame model that has both articulation connectors and dual steering connectors.

BoxBody is Physics3D.Bodies.RigidBody:
    geometry is Physics3D.Geometries.Box:
        size: {3,1,1}
    visual becomes Visuals.Geometries.Box:
        size: geometry.size

SteeredDualJointFrame is MachineModeling.Components.Primitive.Base:
    with Vehicles.Chassis.Articulated.Interfaces.DualJoint
    with Vehicles.Chassis.Articulated.Interfaces.DualSteeringActuators
    sign is Real: 1
    body becomes BoxBody

    upper_joint_connector becomes Physics3D.Interactions.RedirectedMateConnector:
        position.x: sign * body.geometry.size.x * 0.5
        position.z: 0.25
        redirected_parent: body

    lower_joint_connector becomes Physics3D.Interactions.RedirectedMateConnector:
        position.x: sign * body.geometry.size.x * 0.5
        position.z: -0.25
        redirected_parent: body

    left_steering_actuator_connector becomes Physics3D.Interactions.RedirectedMateConnector:
        position.x: sign * body.geometry.size.x * 0.25
        position.y: -body.geometry.size.y * 0.4
        main_axis: {0, 0, 1}
        normal: {1, 0, 0}
        redirected_parent: body

    right_steering_actuator_connector becomes Physics3D.Interactions.RedirectedMateConnector:
        position.x: sign * body.geometry.size.x * 0.25
        position.y: body.geometry.size.y * 0.4
        main_axis: {0, 0, 1}
        normal: {1, 0, 0}
        redirected_parent: body

FrontFrame is SteeredDualJointFrame:
    sign: -1

RearFrame is SteeredDualJointFrame:
    sign: 1

Step 2: Choose chassis topology

LoaderChassis is Vehicles.Chassis.Articulated.DualPivot:
    front_frame becomes FrontFrame
    rear_frame becomes RearFrame

    frame_connection.upper_pivot becomes MachineModeling.Connections.Pivot.Hinge:
        hinge.initial_angle: 0

    frame_connection.lower_pivot becomes MachineModeling.Connections.Pivot.Hinge:
        hinge.initial_angle: 0

Use this when you need the extra center link and two-stage articulation.

LinkBody is Physics3D.Bodies.RigidBody:
    geometry is Physics3D.Geometries.Cylinder:
        radius: 0.2
        height: 1.0

LinkFrame is MachineModeling.Components.Primitive.Base:
    with Vehicles.Chassis.Articulated.Interfaces.DualJoint
    with Vehicles.Chassis.Articulated.Interfaces.SingleJoint
    with Vehicles.Chassis.Articulated.Interfaces.DualSteeringActuators
    body becomes LinkBody

    upper_joint_connector becomes Physics3D.Interactions.RedirectedMateConnector:
        position.x: body.geometry.height * 0.5
        position.z: 0.25
        redirected_parent: body

    lower_joint_connector becomes Physics3D.Interactions.RedirectedMateConnector:
        position.x: body.geometry.height * 0.5
        position.z: -0.25
        redirected_parent: body

    joint_connector becomes Physics3D.Interactions.RedirectedMateConnector:
        position.x: -body.geometry.height * 0.5
        main_axis: {1, 0, 0}
        redirected_parent: body

    left_steering_actuator_connector becomes Physics3D.Interactions.RedirectedMateConnector:
        position.x: body.geometry.height * 0.25
        position.y: -body.geometry.radius * 0.75
        main_axis: {0, 0, 1}
        normal: {1, 0, 0}
        redirected_parent: body

    right_steering_actuator_connector becomes Physics3D.Interactions.RedirectedMateConnector:
        position.x: body.geometry.height * 0.25
        position.y: body.geometry.radius * 0.75
        main_axis: {0, 0, 1}
        normal: {1, 0, 0}
        redirected_parent: body

RearSingleJointFrame is MachineModeling.Components.Primitive.Base:
    with Vehicles.Chassis.Articulated.Interfaces.SingleJoint
    body becomes BoxBody
    joint_connector becomes Physics3D.Interactions.RedirectedMateConnector:
        position.x: body.geometry.size.x * 0.5
        main_axis: {1, 0, 0}
        redirected_parent: body

LoaderChassis is Vehicles.Chassis.Articulated.IntermediateLink:
    front_frame becomes FrontFrame
    link becomes LinkFrame
    rear_frame becomes RearSingleJointFrame

    frame_connection.link: link
    frame_connection.to_link.front_frame: front_frame
    frame_connection.to_link.rear_frame: link
    frame_connection.to_link.upper_from_connector: front_frame.upper_joint_connector
    frame_connection.to_link.lower_from_connector: front_frame.lower_joint_connector
    frame_connection.to_link.upper_to_connector: link.upper_joint_connector
    frame_connection.to_link.lower_to_connector: link.lower_joint_connector

    frame_connection.to_link.upper_pivot becomes MachineModeling.Connections.Pivot.Hinge:
        hinge.initial_angle: 0

    frame_connection.to_link.lower_pivot becomes MachineModeling.Connections.Pivot.Hinge:
        hinge.initial_angle: 0

Step 3: Choose steering actuator model

Variant 1: Higher fidelity DualCylinder

DualCylinder is a cylinder-based steering layout. In many wheel-loader setups you will specialize each actuator with VelocityMotor.

For DualPivot chassis:

Loader is Vehicles.Base:
    chassis becomes LoaderChassis:
        local_transform.position: {0,0,0}

    steering is Vehicles.Steering.Articulated.DualCylinder:
        left_front_connector: chassis.front_frame.left_steering_actuator_connector
        right_front_connector: chassis.front_frame.right_steering_actuator_connector
        left_rear_connector: chassis.rear_frame.left_steering_actuator_connector
        right_rear_connector: chassis.rear_frame.right_steering_actuator_connector

        rod_diameter: 0.1
        barrel_diameter: 0.2
        stroke_length: 1
        min_length: 1

        left_steering_actuator becomes MachineModeling.Actuators.Linear.Cylinder with MachineModeling.Actuators.Linear.Traits.VelocityMotor
        right_steering_actuator becomes MachineModeling.Actuators.Linear.Cylinder with MachineModeling.Actuators.Linear.Traits.VelocityMotor

For IntermediateLink chassis, connect steering between front_frame and link:

Loader is Vehicles.Base:
    chassis becomes LoaderChassis:
        local_transform.position: {0,0,0}

    steering is Vehicles.Steering.Articulated.DualCylinder:
        left_front_connector: chassis.front_frame.left_steering_actuator_connector
        right_front_connector: chassis.front_frame.right_steering_actuator_connector
        left_rear_connector: chassis.link.left_steering_actuator_connector
        right_rear_connector: chassis.link.right_steering_actuator_connector

        rod_diameter: 0.1
        barrel_diameter: 0.2
        stroke_length: 1
        min_length: 1

        left_steering_actuator becomes MachineModeling.Actuators.Linear.Cylinder with MachineModeling.Actuators.Linear.Traits.VelocityMotor
        right_steering_actuator becomes MachineModeling.Actuators.Linear.Cylinder with MachineModeling.Actuators.Linear.Traits.VelocityMotor

Variant 2: Lower fidelity DualDistance

Use this when you want simpler steering mechanics.

For DualPivot chassis:

Loader is Vehicles.Base:
    chassis becomes LoaderChassis:
        local_transform.position: {0,0,0}

    steering is Vehicles.Steering.Articulated.DualDistance:
        left_front_connector: chassis.front_frame.left_steering_actuator_connector
        right_front_connector: chassis.front_frame.right_steering_actuator_connector
        left_rear_connector: chassis.rear_frame.left_steering_actuator_connector
        right_rear_connector: chassis.rear_frame.right_steering_actuator_connector

        stroke_length: 1
        min_length: 1

        left_steering_actuator becomes MachineModeling.Actuators.Linear.Distance:
            source.connectors: [left_front_connector, left_rear_connector]
        right_steering_actuator becomes MachineModeling.Actuators.Linear.Distance:
            source.connectors: [right_front_connector, right_rear_connector]

For IntermediateLink chassis:

Loader is Vehicles.Base:
    chassis becomes LoaderChassis:
        local_transform.position: {0,0,0}

    steering is Vehicles.Steering.Articulated.DualDistance:
        left_front_connector: chassis.front_frame.left_steering_actuator_connector
        right_front_connector: chassis.front_frame.right_steering_actuator_connector
        left_rear_connector: chassis.link.left_steering_actuator_connector
        right_rear_connector: chassis.link.right_steering_actuator_connector

        stroke_length: 1
        min_length: 1

        left_steering_actuator becomes MachineModeling.Actuators.Linear.Distance:
            source.connectors: [left_front_connector, left_rear_connector]
        right_steering_actuator becomes MachineModeling.Actuators.Linear.Distance:
            source.connectors: [right_front_connector, right_rear_connector]

Step 4: Disable internal collisions

For articulated assemblies, it is common to disable collisions between internal loader parts. This avoids self-collision chatter between connected bodies while still allowing external collisions. The snippets below assume steering is already defined on Loader (as in Step 3).

For DualPivot loaders with DualCylinder steering:

Loader is Vehicles.Base:
    chassis becomes LoaderChassis:
        local_transform.position: {0,0,0}

    internal_collision_group is Simulation.CollisionGroup:
        systems: [steering]
        bodies: [chassis.front_frame.body, chassis.rear_frame.body]

    disable_internal_collisions is Simulation.DisableCollisionPair:
        group1: internal_collision_group
        group2: internal_collision_group

For IntermediateLink loaders with DualCylinder steering:

Loader is Vehicles.Base:
    chassis becomes LoaderChassis:
        local_transform.position: {0,0,0}

    internal_collision_group is Simulation.CollisionGroup:
        systems: [steering]
        bodies: [chassis.front_frame.body, chassis.link.body, chassis.rear_frame.body]

    disable_internal_collisions is Simulation.DisableCollisionPair:
        group1: internal_collision_group
        group2: internal_collision_group

Step 5: Assemble complete fidelity presets

Typical wheel-loader presets:

  • Fast prototype
    • Chassis: DualPivot
    • Steering: DualDistance
  • Balanced
    • Chassis: IntermediateLink
    • Steering: DualDistance
  • Detailed steering geometry
    • Chassis: DualPivot
    • Steering: DualCylinder + VelocityMotor trait
  • High articulation detail
    • Chassis: IntermediateLink
    • Steering: DualCylinder + VelocityMotor trait

Notes

  • Keep steering connector main_axis aligned with intended actuator axis and keep normal orthogonal.
  • If using IntermediateLink, verify frame_connection.link and nested to_link.* assignments are set.
  • For DualDistance, set source.connectors on each steering actuator.
  • Add visuals that match contact geometries to keep debug rendering and physical shapes consistent.
  • Use one internal collision group and disable collisions inside it for connected loader parts, including steering cylinder bodies.
  • The examples above are based on working chassis/steering setups used in tests/Vehicles/TestChassis.cpp.
OpenPLX is a work in progress. This draft version will evolve with user feedback and experience. We welcome your input and collaboration.
X