YAML schema for Chrono model specification

A Chrono YAML model file defines a mechanical system and contains two main objects:

  • The Chrono version (chrono-version) that is compatible with the YAML model specification. This is a string of the form M.m (major.minor) or M.m.p (major-minor-patch), although only the two fileds are verified for compatibility.
  • The model object that lists all physics items in the Chrono model.

Model specification

The model object in a Chrono YAML model specification file defines:

  1. Bodies: (Required)rigid bodies that carry mass and inertia and, optionally, collision and visualization geometry
  2. Joints: connection between a pair of bodies, specified either as a kinematic (ideal) joint or as a bushing
  3. Passive force elements: translational and rotational linear or non-linear spring-damper force elements acting between two rigid bodies
  4. Motors and actuators:
    • translational and rotational motors acting between two rigid bodies at the position (displacement or angle), velocity (linear or angular speed), or force (force or torque) levels. Motors are specified through a time function for the control input (position, velocity, or force)
    • external actuators
  5. Constraints: additional constraint equations between bodies
  6. External loads: external loads applied to bodies
Enum values for various object types in the model description YAML file can be provided using any desired case. For example, a "point-line" joint can be specified using any of point_line, POINT_LINE, Point_Line, POinT_liNE, etc.

The table below lists the main fields of the model object:

Property Description Type Available Values Required Default
name Optional model name for identification string No 'YAML model'
angle_degrees Whether angles are in degrees (true) or radians (false) boolean No true
data_path Configuration for data file locations object, see below No using absolute paths
bodies Array of body objects array[body] Yes
joints Array of joint objects array[joint] No
constraints Array of constraint objects array[constraint] No
tsdas Array of TSDA (translational spring-damper) objects array[tsda] No
rsdas Array of RSDA (rotational spring-damper) objects array[rsda] No
motors Array of motor objects array[motor] No
body_loads Array of external loads applied to bodies array[body_load] No

The data_path object can have the following fields if specified:

Field Description Type Available Values Required Default
type Type of data path string RELATIVE or ABSOLUTE Yes
root Root directory for data file locations string No . (current directory)

Bodies

Each body represents a physical object in the simulation with the following properties:

Property Description Type Available Values Required Default
name Unique identifier for the body string Yes
fixed Indicates if body fixed relative to global frame boolean No false
mass Mass in kg double Yes, if body not fixed
com->location Origin of the COM frame relative to body reference frame array[3] No [0, 0, 0]
com->orientation Orientation of the COM frame relative to body reference frame array[3] or array[4] No identity rotation
inertia->moments Moments of inertia [Ixx, Iyy, Izz] relative to centroidal frame array[3] Yes, if body not fixed
inertia->products Products of inertia [Ixy, Iyz, Izx] relative to centroidal frame array[3] No [0, 0, 0]
location Origin of the body reference frame, relative to model frame array[3] Yes
orientation Orientation of the body reference frame relative to model frame array[3] or array[4] No identity rotation
initial_linear_velocity Initial linear velocity of the body reference frame array[3] No [0, 0, 0]
initial_angular_velocity Initial angular velocity of the body reference frame, expressed in local body frame array[3] No [0, 0, 0]
contact List of contact materials, materials and collision shapes, shapes object, see below No no contact
visualization List of visualization shapes, shapes object, see below No no visualization

Note: orientation can be specified as Euler Cardan angles [yaw, pitch, roll] or quaternion [e0, e1, e2, e3]

Body Contact Properties

The collision of a body is specified through a list of contact material, materials and a list of collision shapes, shapes. The model can have more shapes than materials, and the user need to specify which shape is associated with which material. Depending on the contact method, smooth contact formulation (SMC) or non-smooth contact formulation (NSC), the same contact paramters, such as coefficient_of_friction and coefficient_of_restitution, can result in different physics. When using the SMC formulation, the user can specify material-based properties, such as Youngs_modulus and Poisson_ratio, or spring-damper coefficients for modeling contact, such as normal_stiffness and normal_damping.

Property Description Type Available Values Required Default
materials Contact material properties array[material], see Contact Material below Yes
shapes Collision shapes for contact detection array[shape], see Collision Shape below Yes

Contact Material

Property Description Type Available Values Required Default
name Unique identifier for the material string Yes
coefficient_of_friction Friction coefficient double No 0.8
coefficient_of_restitution Coefficient of restitution double No 0.01
properties (SMC only) contact material-based properties, such as Young's modulus and Poisson's ratio object No see below
Coefficients (SMC only) contact spring-damper coefficients, such as normal stiffness and damping object No see below


Properties for material->properties:

Property Description Type Available Values Required Default
Youngs_modulus Young's modulus of the material double Yes 2e7 if properties not specified
Poisson_ratio Poisson's ratio of the material double Yes 0.3 if properties not specified


Properties for material->Coefficients:

Property Description Type Available Values Required Default
normal_stiffness Normal stiffness coefficient double Yes 2e5 if Coefficients not specified
normal_damping Normal damping coefficient double Yes 40 if Coefficients not specified
tangential_stiffness Tangential stiffness coefficient double Yes 2e5 if Coefficients not specified
tangential_damping Tangential damping coefficient double Yes 20 if Coefficients not specified

Collision Shape

Property Description Type Available Values Required Default
type Collision shape type string SPHERE, BOX,
CYLINDER, MESH,
HULL
Yes
material Name of the contact material used for the shape, see above string Yes
location Shape location relative to body reference frame array[3] Yes , except for MESH [0, 0, 0] for MESH
orientation Shape orientation relative to body reference frame array[3] or array[4] Yes , except for MESH identity rotation for MESH
radius Radius for SPHERE and CYLINDER shapes double Yes
dimensions Dimensions [length, width, height] for BOX shape array[3] Yes
axis Axis direction for CYLINDER shape array[3] Yes
length Length for CYLINDER shape double Yes
filename Filename for HULL and MESH shapes string Yes
contact_radius Contact radius for MESH shape double No 0
scale Scale factor for MESH shape double No 1.0

Body Visualization Properties

The visualization of the body can either be one single model_file and/or a list of shapes (of type SPHERE, BOX, CYLINDER,or MESH). If provided, a model_file is passed directly, as-is to the run-time visualization system. On the other hand, a MESH shape is assumed to be provided only through an OBJ Wavefront file and also provides support for translating, rotating, and scaling.

Property Description Type Available Values Required Default
model_file Path to the model file for visualization string No
shapes List of shapes for visualization array, see below No

Visualization Shapes

Property Description Type Available Values Required Default
type Visualization shape type string SPHERE, BOX,
CYLINDER, MESH
Yes
location Shape location relative to body reference frame array[3] Yes , except for MESH [0, 0, 0] for MESH
orientation Shape orientation relative to body reference frame array[3] or array[4] Yes , except for MESH identity rotation for MESH
radius Radius for SPHERE and CYLINDER shapes double Yes
dimensions Dimensions [length, width, height] for BOX shape array[3] Yes
axis Axis direction for CYLINDER shape array[3] Yes
length Length for CYLINDER shape double Yes
filename Filename for MESH shapes string Yes
scale Scale factor for MESH shape double No 1.0
color Color of the shape in RGB format [r, g, b] array[3] No [-1, -1, -1]

Joints

Joints are connection between two bodies and constrain their relative motion. They can be represented through constraints (ideal kinematic joints) or through stiff compliance (bushings). Currently supported joint type are: LOCK, REVOLUTE, SPHERICAL, PRISMATIC, UNIVERSAL, POINT_LINE, POINT_PLANE.

Property Description Type Available Values Required Default
type Joint type string LOCK,
REVOLUTE,
SPHERICAL,
PRISMATIC,
UNIVERSAL,
POINT_LINE,
POINT_PLANE
Yes
name Unique identifier for the joint string Yes
body1 Name of the first body to connect string Yes
body2 Name of the second body to connect string Yes
location Joint location array[3] Yes
axis Axis of motion for revolute/prismatic joints array[3] Yes
axis1 First axis for universal joints array[3] Yes
axis2 Second axis for universal joints array[3] Yes
bushing_data Bushing compliance data; if not present, the joint is kinematic object No no bushing

The bushing_data models compliance behavior along the joint's constrained degrees of freedom (i.e., relaxations of the rigid constraints for an ideal kinematic joint). Note that a joint of type PRISMATIC, POINT_LINE or POINT_PLANE is prohibited.

For the constrained DOF, one can specify stiffness and damping coefficients,

Property Description Type Available Values Required Default
stiffness_linear Linear stiffness coefficient for "constrained" translational DOFs double Yes
damping_linear Linear damping coefficient for "constrained" translational DOFs double Yes
stiffness_rotational Rotational stiffness coefficient for "constrained" rotational DOFs double Yes
damping_rotational Rotational damping coefficient for "constrained" rotational DOFs double Yes
DOF Degree of freedom specific properties object No all 0.0

Optionally, one can apply compliance to the unconstrained DOF using a nested DOF object, for example:

bushing_data:
stiffness_linear: 7e7
damping_linear: 0.35e5
stiffness_rotational: 1e5
damping_rotational: 5e3
DOF:
stiffness_linear: 5000
damping_linear: 50
stiffness_rotational: 500
damping_rotational: 25

If the DOF object is not present, the linear and rotational stiffness and damping in the direction of the unconstrained DOF of the bushing are all set to 0.0.

Constraints

Constraints connect two bodies and constrain their relative motion. Supported constraint type are: DISTANCE, REVOLUTE-SPHERICAL, REVOLUTE-TRANSLATIONAL.

Property Description Type Available Values Required Default
type Constraint type string DISTANCE,
REVOLUTE-SPHERICAL,
REVOLUTE-TRANSLATIONAL
Yes
name Unique identifier for the constraint string Yes
body1 Name of the first body to connect string Yes
body2 Name of the second body to connect string Yes
point1 Point on body1 expressed in global frame array[3] Yes
point2 Point on body2 expressed in global frame array[3] Yes

Passive spring-damper force elements

There are two types of spring-damper elements, translational (TSDA) and rotational (RSDA).

Translational spring-dampers

TSDA elements apply forces on the connected bodies. In the YAML specification file, they are listed in an array tsdas containing objects with the following properties:

Property Description Type Available Values Required Default
name Unique identifier for the force element string Yes
body1 Name of the first body to connect string Yes
body2 Name of the second body to connect string Yes
point1 Point on body1 expressed in global frame [x,y,z] array[3] Yes
point2 Point on body2 expressed in global frame [x,y,z] array[3] Yes
free_length TSDA free length double Yes
preload preload force double No 0
minimum_length Minimum TSDA length double No
maximum_length Maximum TSDA length double No
visualization Visualization properties of the TSDA element object No no visualization

For linear spring-dampers, use the spring_coefficient and damping_coefficient properties. For example:

tsdas:
- name: linear_spring_damper
body1: first_body
body2: second_body
point1: [6.5, 0, 0]
point2: [5.5, 0, 0]
spring_coefficient: 50.0
damping_coefficient: 5.0
free_length: 1.0
visualization:
type: SPRING
radius: 0.05
resolution: 80
turns: 15

For nonlinear behavior, use spring_curve_data and/or damping_curve_data and/or the pair deformation/map_data. These properties allow specification of spring-damper characteristics as tabular data (which will be linearly interpolated by Chrono at run-time). For example:

tsdas:
- name: nonlinear_spring_damper
body1: first_body
body2: second_body
point1: [6.5, 0, 0]
point2: [5.5, 0, 0]
deformation: [ 0.273304, 0.278384, 0.283464, 0.288544, 0.293624, 0.324104, 0.343002, 0.361899, 0.380797, 0.399694, 0.418592, 0.423672, 0.428752, 0.433832, 0.438912 ],
map_data: [
[ -0.666667, -5691.62, -5691.62, -5691.62, -5691.62, -5691.62, -9690.35, -9690.35, -9690.35, -9690.35, -9690.35, -9690.35, -5691.62, -5691.62, -5691.62, -5691.62 ],
[ -0.333333, -2845.81, -2845.81, -2845.81, -2845.81, -2845.81, -4845.17, -4845.17, -4845.17, -4845.17, -4845.17, -4845.17, -2845.81, -2845.81, -2845.81, -2845.81 ],
[ 0.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 ],
[ 0.333333, 21307.1, 21307.1, 21307.1, 21307.1, 21307.1, 11675.1, 11675.1, 11675.1, 11675.1, 11675.1, 11675.1, 21307.1, 21307.1, 21307.1, 21307.1 ],
[ 0.666667, 42614.2, 42614.2, 42614.2, 42614.2, 42614.2, 23350.2, 23350.2, 23350.2, 23350.2, 23350.2, 23350.2, 42614.2, 42614.2, 42614.2, 42614.2 ]
]

Optionally, a visualization object specifies rendering of the TSDA element:

Property Description Type Available Values Required Default
type Type of visualization geometry string SEGMENT,SPRING YES
color RGB color of the element [r, g, b] array[3] No [0, 0, 0]
radius Radius of the visualized TSDA geometry (if SPRING) double No 0.05
resolution Number of subdivisions along one coil turn (if SPRING) integer No 65
turns Number of coil turns (if SPRING) integer No 5

Rotational spring-dampers

Rotational spring-damper elements (RSDA) apply torques between the two connected bodies. In the YAML peicifcation file, they are listed in an array rsdas containing objects with the following properties:

Property Description Type Available Values Required Default
name Unique identifier for the element string Yes
body1 Name of the first body to connect string Yes
body2 Name of the second body to connect string Yes
location RSDA location expressed in global frame [x,y,z] array[3] No [0, 0, 0]
axis RSDA axis expressed in global frame [x,y,z] array[3] Yes
free_angle RSDA free angle double Yes
preload preload torque double No 0
spring_coefficient Linear spring coefficient double Yes for linear spring
damping_coefficient Linear damping coefficient double Yes for linear damper
spring_curve_data Nonlinear spring curve data [[angle, torque], ...] array, see above Yes for nonlinear spring
damping_curve_data Nonlinear damping curve data [[angular velocity, torque], ...] array, see above Yes for nonlinear damper

Linear or non-linear RSDA torques are specified similarly to corresponding linear or non-linear forces for a TSDA.

Body Loads

Body loads represent external forces or torques applied to specific bodies in the simulation.

Property Description Type Available Values Required Default
name Unique identifier for the body load string Yes
type Type of body load string FORCE, TORQUE Yes
body Name of the body to which the load is applied string Yes
load Load vector for force or torque array[3] Yes
local_load Whether load is applied in local body frame (true) or global frame (false) boolean Yes
point (FORCE only) Location of the applied load array[3] Yes for FORCE
local_point (FORCE only) Whether point is specified in local body frame (true) or global frame (false) boolean Yes for FORCE

Motors

Motors are used to apply forces or torques to bodies. Supported motor type are: LINEAR, ROTATION. LINEAR motors apply forces along a specified axis, while ROTATION motors apply torques.

Property Description Type Available Values Required Default
name Unique identifier for the motor string Yes
type Type of motor string LINEAR,
ROTATION
Yes
body1 Name of the first body to connect string Yes
body2 Name of the second body to connect string Yes
location Motor location expressed in the global frame at [x,y,z] array[3] Yes
axis Motor axis expressed in the global frame at [x,y,z] array[3] Yes
actuation_type Type of actuation string POSITION,
SPEED,
FORCE
Yes
actuation_function Function of time defining the actuation object Yes
guide Guide constraint for linear motors string FREE,
PRISMATIC,
SPHERICAL
No PRISMATIC
spindle Spindle constraint for rotational motors string FREE,
REVOLUTE,
CYLINDRICAL
No REVOLUTE

Functions

A function object is used to specify actuation inputs. The only required field is type, which determines which additional fields are valid. Supported function types include:

  • CONSTANT defines a function with a fixed value;
  • POLYNOMIAL defines a polynomial function of the form f(x) = a₀ + a₁x + a₂x² + ... using the coefficients field: [a₀, a₁, a₂, ...];
  • SINE defines a sinusoidal function with amplitude, frequency and phase;
  • RAMP defines a ramp function with slope and intercept;
  • DATA interpolates a series of data points, for example:
type: DATA
data:
- [0.0, 0.0]
- [1.0, 5.0]
- [2.0, 2.5]

All function types can include an optional repeat field to periodically replicate the function. For example:

repeat:
start: 1.0
width: 2.0
shift: 3.0

YAML schema

The YAML model specification file must follow the data/yaml/schema/model.schema.yaml provided in the Chrono data directory:

# =============================================================================
# PROJECT CHRONO - http://projectchrono.org
#
# Copyright (c) 2025 projectchrono.org
# All rights reserved.
#
# Use of this source code is governed by a BSD-style license that can be found
# in the LICENSE file at the top level of the distribution and at
# http://projectchrono.org/license-chrono.txt.
# =============================================================================
#
# Schema for a Chrono YAML model specification file.
# The `chrono-version` must match the Chrono major and minor version numbers.
# The `model` object contains the schema for the model YAML specification.
#
# Notes:
# - Chrono is unit-independent.
# While any consistent set of units is acceptable, most models are specified
# in SI units. For convenience, the Chrono YAML specification allows definition
# of angles in radians or degrees.
#
# =============================================================================
chrono-version:
type: string
description: Chrono version compatible with this YAML model specification (M.m or M.m.p)
# -----------------------------------------------------------------------------
# Definitions of common Chrono types
# -----------------------------------------------------------------------------
# Specification of a ChVector3d
vector3d: &VECTOR3D
type: array
items:
type: number
minItems: 3
maxItems: 3
# Specification of a 3D rotation
# A rotation can be provided as:
# - an Euler angle sequence [yaw, pitch, roll], with angles assumed in radians or degrees, or
# - a unit quaternion [e0, e1, e2, e3]
orientation3d: &ORIENTATION3D
type: array
description: Frame orientation as Euler angles or as quaternion
items:
type: number
minItems: 3
maxItems: 4
# Specification of a color
color: &COLOR
type: array
description: RGB color [r, g, b]
items:
type: number
minimum: 0
maximum: 1
minItems: 3
maxItems: 3
# Specification of an inertia matrix
inertia33: &INERTIA33
type: object
description: Inertia moments and products
properties:
moments:
type: array
description: Moments of inertia [Ixx, Iyy, Izz]
items:
type: number
minimum: 0
minItems: 3
maxItems: 3
products:
type: array
description: Products of inertia [Ixy, Ixz, Iyz]
items:
type: number
default: 0
minItems: 3
maxItems: 3
# Specification of a function of one variable
function: &FUNCTION
type: object
description: Function of one variable
required: [type]
properties:
type:
type: string
enum: [CONSTANT, POLYNOMIAL, SINE, RAMP, DATA]
description: Function type
repeat:
type: object
description: Periodic replication of the underlying function
start:
type: number
description: Slice start position
width:
type: number
description: Slice width
shift:
type: number
description: Slice shift
value:
type: number
description: Constant value for CONSTANT type
coefficients:
type: array
description: Coefficents for POLYNOMIAL type
items:
type: number
minItems: 2
amplitude:
type: number
description: Amplitude for SINE type
frequency:
type: number
description: Frequency for SINE type
phase:
type: number
description: Phase for SINE type
default: 0.0
slope:
type: number
description: Slope for RAMP type
intercept:
type: number
description: Intercept value for RAMP type
default: 0.0
data:
<<: *DATA_ARRAY_2
description: Interpolation data points for DATA type [[x, f(x)], ...]
# Specification of a data array with 2 columns
data_array_2: &DATA_ARRAY_2
type: array
description: Array of number pairs
items:
type: array
items:
type: number
minItems: 2
maxItems: 2
# Specification of a data array with 3 columns
data_array_3: &DATA_ARRAY_3
type: array
description: Array of number 3-tuples
items:
type: array
items:
type: number
minItems: 3
maxItems: 3
# Specification of a data array with N columns
data_array_N: &DATA_ARRAY_N
type: array
description: Array of N-tuples
items:
type: array
items:
type: number
minItems: 1
# Specification of geometric shapes for visualization and collision
shape : &SHAPE
type: object
properties:
type:
type: string
description: Geometric shape type
enum: [SPHERE, BOX, CYLINDER, HULL, MESH]
location:
<<: *VECTOR3D
description: Shape location relative to body reference frame
orientation:
<<: *ORIENTATION3D
description: Shape orientation relative to body reference frame
dimensions:
<<: *VECTOR3D
description: Length, width, and height (required for BOX type)
radius:
type: number
description: Radius of the sphere (required for SPHERE or CYLINDER type)
minimum: 0.0
length:
type: number
description: Length (required for CYLINDER type)
minimum: 0.0
axis:
<<: *VECTOR3D
description: Axis direction expressed in body reference frame (required for CYLINDER type)
filename:
type: string
description: 3D data file name (required for MESH or HULL type)
scale:
type: number
description: Scale factor (for MESH type)
default: 1.0
visualization_shape: &VISUALIZATION_SHAPE
type: object
description: Visualization shape
required: [type]
<<: *SHAPE
color:
<<: *COLOR
description: Diffuse color for this shape
default: [0.75, 0.75, 0.75]
colision_shape: &COLLISION_SHAPE
type: object
description: Collision shape
required: [type, material]
<<: *SHAPE
material:
type: string
description: Name of the material used for this collision shape
contact_radius:
type: number
description: Contact radius for MESH shape
default: 0.0
minimum: 0.0
# Specification of contact material properties
contact_material: &CONTACT_MATERIAL
required: [name]
name:
type: string
description: Unique identifier for the material
coefficient_of_friction:
type: number
description: Friction coefficient
default: 0.8
coefficient_of_restitution:
type: number
description: Coefficient of restitution
default: 0.01
properties:
type: object
description: material based properties for SMC contact
required: [Youngs_modulus, Poisson_ratio]
properties:
Youngs_modulus:
type: number
description: Young's modulus of the material
Poisson_ratio:
type: number
description: Poisson's ratio of the material
Coefficients:
type: object
description: normal and tangential stiffness and damping coefficients for SMC contact
required: [normal_stiffness, normal_damping, tangential_stiffness, tangential_damping]
properties:
normal_stiffness:
type: number
description: Normal stiffness coefficient
normal_damping:
type: number
description: Normal damping coefficient
tangential_stiffness:
type: number
description: Tangential stiffness coefficient
tangential_damping:
type: number
description: Tangential damping coefficient
# -----------------------------------------------------------------------------
# Definition of a Chrono multibody model
# -----------------------------------------------------------------------------
model:
type: object
description: Definition of a Chrono multibody model
required: [bodies]
properties:
name:
type: string
description: Name of the model
default: ''
angle_degrees:
type: boolean
description: Whether angles are specified in degrees (true) or radians (false)
default: true
data_path:
type: object
description: Location of data files in the model specification.
required: [type]
properties:
type:
type: string
description: Mode for data file location
enum: [ABSOLUTE, RELATIVE]
default: ABSOLUTE
root:
type: string
description: Root of data files, relatiuve to location of this script
default: "."
bodies:
type: array
description: List of bodies in the system
items:
type: object
required: [name, location]
properties:
name:
type: string
description: Unique identifier for the body
fixed:
type: boolean
description: Whether the body is fixed to ground
default: false
location:
<<: *VECTOR3D
description: Initial body reference frame origin relative to global frame
orientation:
<<: *ORIENTATION3D
description: Initial body reference frame orientation relative to global frame
default: [0, 0, 0]
mass:
type: number
description: Mass of the body
minimum: 0
com:
type: object
description: Center of mass (COM) frame
properties:
location:
<<: *VECTOR3D
description: COM frame origin relative to body reference frame
default: [0, 0, 0]
orientation:
<<: *ORIENTATION3D
description: COM frame orientation relative to body reference frame
default: [1, 0, 0, 0]
inertia:
<<: *INERTIA33
description: Body inertia properties
contact:
type: object
description: Contact material and collision geometry
required: [materials, shapes]
properties:
materials:
type: array
description: List of contact material properties
items:
<<: *CONTACT_MATERIAL
shapes:
type: array
description: List of collision shapes
items:
<<: *COLLISION_SHAPE
visualization:
type: object
description: Visualization geometry
properties:
model_file:
type: string
description: Path to a model file for visualization
shapes:
type: array
description: List of visualization shapes
items:
<<: *VISUALIZATION_SHAPE
joints:
type: array
description: List of joints connecting bodies
items:
type: object
required: [name, type, body1, body2, location]
properties:
name:
type: string
description: Unique identifier for the joint
type:
type: string
description: Type of joint
enum: [LOCK, REVOLUTE, SPHERICAL, PRISMATIC, UNIVERSAL, POINT_LINE, POINT_PLANE ]
body1:
type: string
description: Name of the first body to connect
body2:
type: string
description: Name of the second body to connect
location:
type: array
description: Joint location
items:
type: number
minItems: 3
maxItems: 3
axis:
<<: *VECTOR3D
description: Axis of motion for revolute/prismatic joints
axis1:
<<: *VECTOR3D
description: First axis for universal joint
axis2:
<<: *VECTOR3D
description: Second axis for universal joint
bushing_data:
type: object
description: Bushing properties
properties:
stiffness_linear:
type: number
description: Linear stiffness coefficient for "constrained" translational DOFs
damping_linear:
type: number
description: Linear damping coefficient for "constrained" translational DOFs
stiffness_rotational:
type: number
description: Rotational stiffness coefficient for "constrained" rotational DOFs
damping_rotational:
type: number
description: Rotational damping coefficient for "constrained" rotational DOFs
DOF:
type: object
description: Degree of freedom specific properties
properties:
stiffness_linear:
type: number
description: Linear stiffness coefficient for "unconstrained" translational DOF
damping_linear:
type: number
description: Linear damping coefficient for "unconstrained" translational DOF
stiffness_rotational:
type: number
description: Rotational stiffness coefficient for "unconstrained" rotational DOF
damping_rotational:
type: number
description: Rotational damping coefficient for "unconstrained" rotational DOF
constraints:
type: array
description: List of constraints in the system
items:
type: object
required: [name, type, body1, body2]
properties:
name:
type: string
description: Unique identifier for the constraint
type:
type: string
enum: [DISTANCE, REVOLUTE-SPHERICAL, REVOLUTE-TRANSLATIONAL]
description: Type of constraint
body1:
type: string
description: Name of the first body to connect
body2:
type: string
description: Name of the second body to connect
point1:
<<: *VECTOR3D
description: Point on body1 expressed in global frame
point2:
<<: *VECTOR3D
description: Point on body2 expressed in global frame
tsdas:
type: array
description: List of translational spring-damper (TSDA) elements
items:
type: object
required: [name, body1, body2, point1, point2]
properties:
name:
type: string
description: Unique identifier for the element
body1:
type: string
description: Name of the first body to connect
body2:
type: string
description: Name of the second body to connect
point1:
<<: *VECTOR3D
description: Point on body1 expressed in global frame
point2:
<<: *VECTOR3D
description: Point on body2 expressed in global frame
free_length:
type: number
description: TSDA free length
spring_coefficient:
type: number
description: Linear spring coefficient
damping_coefficient:
type: number
description: Linear damping coefficient
spring_curve_data:
<<: *DATA_ARRAY_2
description: Nonlinear spring curve data [[displacement, force], ...]
damping_curve_data:
<<: *DATA_ARRAY_2
description: Nonlinear damping curve data [[velocity, force], ...]
deformation:
type: array
description: TSDA deformation values for full non-linear map TSDA (required if map_data present)
items:
type: number
minItems: 1
map_data:
<<: *DATA_ARRAY_N
description: TSDA full non-linear map [[velocity, forces[]], ...]
preload:
type: number
description: Preload force
minimum_length:
type: number
description: Minimum TSDA length
maximum_length:
type: number
description: Maximum TSDA length
visualization:
type: object
description: Visualization settings for the element
properties:
type:
type: string
enum: [segment, spring]
description: Type of visualization
radius:
type: number
description: Radius of the visualization element
color:
<<: *COLOR
rsdas:
type: array
description: List of rotational spring-damper (RSDA) elements
items:
type: object
required: [name, body1, body2, axis]
properties:
name:
type: string
description: Unique identifier for the element
body1:
type: string
description: Name of the first body to connect
body2:
type: string
description: Name of the second body to connect
location:
<<: *VECTOR3D
description: RSDA location expressed in global frame
axis:
<<: *VECTOR3D
description: RSDA axis expressed in global frame
free_angle:
type: number
description: RSDA free angle
spring_coefficient:
type: number
description: Linear spring coefficient
damping_coefficient:
type: number
description: Linear damping coefficient
spring_curve_data:
<<: *DATA_ARRAY_2
description: Nonlinear spring curve data [[displacement, force], ...]
damping_curve_data:
<<: *DATA_ARRAY_2
description: Nonlinear damping curve data [[velocity, force], ...]
preload:
type: number
description: Preload torque
motors:
type: array
description: List of motors in the system
items:
type: object
required: [name, type, body1, body2, location, axis, actuation_type, actuation_function]
properties:
name:
type: string
description: Unique identifier for the motor
type:
type: string
enum: [LINEAR, ROTATION]
description: Type of motor
body1:
type: string
description: Name of the first body to connect
body2:
type: string
description: Name of the second body to connect
location:
<<: *VECTOR3D
description: Motor location expressed in global frame
axis:
<<: *VECTOR3D
description: Motor axis expressed in global frame
actuation_type:
type: string
enum: [POSITION, SPEED, FORCE]
description: Type of actuation
actuation_function:
<<: *FUNCTION
description: Function of time defining actuation
guide:
type: string
enum: [FREE, PRISMATIC, SPHERICAL]
description: Guide constraint for linear motor
spindle:
type: string
enum: [FREE, REVOLUTE, CYLINDRICAL]
description: Spindle constraint for rotation motor
body_loads:
type: array
description: List of external loads applied to bodies
items:
type: object
required: [name, type, body, load, local_load]
properties:
name:
type: string
description: Unique identifier for the body load
type:
type: string
enum: [FORCE, TORQUE]
description: Type of body load
body:
type: string
description: Name of the body to which the load is applied
load:
<<: *VECTOR3D
description: Load vector for force or torque
local_load:
type: boolean
description: Whether load is applied in local body frame (true) or global frame (false)
point:
<<: *VECTOR3D
description: (FORCE only) Location of the applied load
local_point:
type: boolean
description: (FORCE only) Whether point is specified in local body frame (true) or global frame (false)