Multibody

Documentation for Multibody.

Welcome to the world of Multibody.jl, a powerful and flexible component of JuliaSim designed to model, analyze, and simulate multibody systems in Julia. As a state-of-the-art tool, Multibody.jl enables users to efficiently study the dynamics of complex mechanical systems in various fields, such as robotics, biomechanics, aerospace, and vehicle dynamics.

Built on top of the Julia language and the JuliaSim suite of tools for modeling, simulation, optimization and control, Multibody.jl harnesses the power of Julia's high-performance computing capabilities, making it a go-to choice for both researchers and engineers who require fast simulations and real-time performance. With an intuitive syntax and a comprehensive set of features, this package seamlessly integrates with other Julia and JuliaSim libraries, enabling users to tackle diverse and sophisticated problems in multibody dynamics.

In this documentation, you will find everything you need to get started with Multibody.jl, from basic component descriptions to detailed examples showcasing the package's capabilities. As you explore this documentation, you'll learn how to create complex models, work with forces and torques, simulate various types of motions, and visualize your results in both 2D and 3D. Whether you are a seasoned researcher or a newcomer to the field, Multibody.jl will empower you to bring your ideas to life and unlock new possibilities in the fascinating world of multibody dynamics.

Notable difference from Modelica

  • The torque variable in Multibody.jl is typically called tau rather than t to not conflict with the often used independent variable t used to denote time.
  • Multibody.jl occasionally requires the user to specify which component should act as the root of the kinematic tree. This only occurs when bodies are connected directly to force components without a joint parallel to the force component.
  • In Multibody.jl, the orientation object of a Frame is accessed using he function ori.

Index

Frames

Multibody.FrameFunction
Frame(; name)

Frame is the fundamental 3D connector in the multibody library. Most components have one or several Frame connectors that can be connected together.

The Frame connector has internal variables for

  • r_0: The position vector from the world frame to the frame origin, resolved in the world frame
  • f: The cut force resolved in the connector frame
  • tau: The cut torque resolved in the connector frame
  • Depending on usage, also rotation and rotational velocity variables.
source

Joints

A joint restricts the number of degrees of freedom (DOF) of a body. For example, a free floating body has 6 DOF, but if it is attached to a Revolute joint, the joint restricts all but one rotational degree of freedom (a revolute joint acts like a hinge). Similarily, a Prismatic joint restricts all but one translational degree of freedom (a prismatic joint acts like a slider).

A Spherical joints restricts all translational degrees of freedom, but allows all rotational degrees of freedom. It thus transmits no torque.

Some joints offer the option to add 1-dimensional components to them by providing the keyword useAxisFlange = true. This allows us to add, e.g., springs, dampers, sensors, and actuators to the joint.

Multibody.FreeMotionMethod
FreeMotion(; name, enforceState = true, sequence, isroot = true, w_rel_a_fixed = false, z_rel_a_fixed = false, phi = 0, phi_d = 0, phi_dd = 0, w_rel_b = 0, r_rel_a = 0, v_rel_a = 0, a_rel_a = 0)

Joint which does not constrain the motion between frame_a and frame_b. Such a joint is only meaningful if the relative distance and orientation between frame_a and frame_b, and their derivatives, shall be used as state.

Note, that bodies such as Body, BodyShape, have potential state variables describing the distance and orientation, and their derivatives, between the world frame and a body fixed frame. Therefore, if these potential state variables are suited, a FreeMotion joint is not needed.

The state of the FreeMotion object consits of:

The relative position vector r_rel_a from the origin of frame_a to the origin of frame_b, resolved in frame_a and the relative velocity v_rel_a of the origin of frame_b with respect to the origin of frame_a, resolved in frame_a (= der(r_rel_a)).

Arguments

  • enforceState: Enforce this joint having state, this is often desired and is the default choice.
  • sequence: Rotation sequence
  • w_rel_a_fixed: = true, if w_rel_a_start are used as initial values, else as guess values
  • z_rel_a_fixed: = true, if z_rel_a_start are used as initial values, else as guess values

Initial condition arguments:

  • phi
  • phi_d
  • phi_dd
  • w_rel_b
  • r_rel_a
  • v_rel_a
  • a_rel_a
source
Multibody.GearConstraintMethod
GearConstraint(; name, ratio, checkTotalPower = false, n_a, n_b, r_a, r_b)

This ideal massless joint provides a gear constraint between frames frame_a and frame_b. The axes of rotation of frame_a and frame_b may be arbitrary.

  • ratio: Gear ratio
  • n_a: Axis of rotation of frame_a
  • n_b: Axis of rotation of frame_b
  • r_a: Vector from frame bearing to frame_a resolved in bearing
  • r_b: Vector from frame bearing to frame_b resolved in bearing
source
Multibody.PrismaticMethod
Prismatic(; name, n = [0, 0, 1], useAxisFlange = false, isroot = true)

Prismatic joint with 1 translational degree-of-freedom

  • n: The axis of motion (unit vector)
  • useAxisFlange: If true, the joint will have two additional frames from Mechanical.Translational, axis and support, between which translational components such as springs and dampers can be connected.
  • isroot: If true, the joint will be considered the root of the system.

If useAxisFlange, flange connectors for ModelicaStandardLibrary.Mechanics.TranslationalModelica are also available:

  • axis: 1-dim. translational flange that drives the joint
  • support: 1-dim. translational flange of the drive support (assumed to be fixed in the world frame, NOT in the joint)

The function returns an ODESystem representing the prismatic joint.

source
Multibody.RevoluteMethod
Revolute(; name, phi0 = 0, w0 = 0, n, useAxisFlange = false)

Revolute joint with 1 rotational degree-of-freedom

  • phi0: Initial angle
  • w0: Iniitial angular velocity
  • n: The axis of rotation
  • useAxisFlange: If true, the joint will have two additional frames from Mechanical.Rotational, axis and support, between which rotational components such as springs and dampers can be connected.

If useAxisFlange, flange connectors for ModelicaStandardLibrary.Mechanics.Rotational are also available:

  • axis: 1-dim. rotational flange that drives the joint
  • support: 1-dim. rotational flange of the drive support (assumed to be fixed in the world frame, NOT in the joint)
source
Multibody.RevolutePlanarLoopConstraintMethod
RevolutePlanarLoopConstraint(; name, n)

Revolute joint that is described by 2 positional constraints for usage in a planar loop (the ambiguous cut-force perpendicular to the loop and the ambiguous cut-torques are set arbitrarily to zero)

Joint where frame_b rotates around axis n which is fixed in frame_a and where this joint is used in a planar loop providing 2 constraint equations on position level.

If a planar loop is present, e.g., consisting of 4 revolute joints where the joint axes are all parallel to each other, then there is no unique mathematical solution if all revolute joints are modelled with Revolute and the symbolic algorithms will fail. The reason is that, e.g., the cut-forces in the revolute joints perpendicular to the planar loop are not uniquely defined when 3-dim. descriptions of revolute joints are used. Usually, an error message will be printed pointing out this situation. In this case, one revolute joint in the loop has to be replaced by model RevolutePlanarLoopCutJoint. The effect is that from the 5 constraints of a 3-dim. revolute joint, 3 constraints are removed and replaced by appropriate known variables (e.g., the force in the direction of the axis of rotation is treated as known with value equal to zero; for standard revolute joints, this force is an unknown quantity).

source
Multibody.RollingWheelMethod
RollingWheel(; name, radius, m, I_axis, I_long, width=0.035, x0, y0, kwargs...)

Ideal rolling wheel on flat surface z=0 (5 positional, 3 velocity degrees of freedom)

A wheel rolling on the x-y plane of the world frame including wheel mass. The rolling contact is considered being ideal, i.e. there is no slip between the wheel and the ground. The wheel can not take off but it can incline toward the ground. The frame frame_a is placed in the wheel center point and rotates with the wheel itself.

Arguments and parameters:

  • name: Name of the rolling wheel component
  • radius: Radius of the wheel
  • m: Mass of the wheel
  • I_axis: Moment of inertia of the wheel along its axis
  • I_long: Moment of inertia of the wheel perpendicular to its axis
  • width: Width of the wheel (default: 0.035)
  • x0: Initial x-position of the wheel axis
  • y0: Initial y-position of the wheel axis
  • kwargs...: Additional keyword arguments passed to the RollingWheelJoint function

Variables:

  • x: x-position of the wheel axis
  • y: y-position of the wheel axis
  • angles: Angles to rotate world-frame into frame_a around z-, y-, x-axis
  • der_angles: Derivatives of angles

Named components:

  • frame_a: Frame for the wheel component
  • rollingWheel: Rolling wheel joint representing the wheel's contact with the road surface
source
Multibody.RollingWheelJointMethod
RollingWheelJoint(; name, radius, angles, x0, y0, z0)

Joint (no mass, no inertia) that describes an ideal rolling wheel (rolling on the plane z=0). See RollingWheel for a realistic wheel model with inertia.

A joint for a wheel rolling on the x-y plane of the world frame. The rolling contact is considered being ideal, i.e. there is no slip between the wheel and the ground. This is simply gained by two non-holonomic constraint equations on velocity level defined for both longitudinal and lateral direction of the wheel. There is also a holonomic constraint equation on position level granting a permanent contact of the wheel to the ground, i.e. the wheel can not take off.

The origin of the frame frame_a is placed in the intersection of the wheel spin axis with the wheel middle plane and rotates with the wheel itself. The y-axis of frame_a is identical with the wheel spin axis, i.e. the wheel rotates about y-axis of frame_a. A wheel body collecting the mass and inertia should be connected to this frame.

Arguments and parameters:

name: Name of the rolling wheel joint component radius: Radius of the wheel angles: Angles to rotate world-frame into frame_a around z-, y-, x-axis

Variables:

  • x: x-position of the wheel axis
  • y: y-position of the wheel axis
  • z: z-position of the wheel axis
  • angles: Angles to rotate world-frame into frame_a around z-, y-, x-axis
  • der_angles: Derivatives of angles
  • r_road_0: Position vector from world frame to contact point on road, resolved in world frame
  • f_wheel_0: Force vector on wheel, resolved in world frame
  • f_n: Contact force acting on wheel in normal direction
  • f_lat: Contact force acting on wheel in lateral direction
  • f_long: Contact force acting on wheel in longitudinal direction
  • err: Absolute value of (r_road_0 - frame_a.r_0) - radius (must be zero; used for checking)
  • e_axis_0: Unit vector along wheel axis, resolved in world frame
  • delta_0: Distance vector from wheel center to contact point
  • e_n_0: Unit vector in normal direction of road at contact point, resolved in world frame
  • e_lat_0: Unit vector in lateral direction of road at contact point, resolved in world frame
  • e_long_0: Unit vector in longitudinal direction of road at contact point, resolved in world frame
  • s: Road surface parameter 1
  • w: Road surface parameter 2
  • e_s_0: Road heading at (s,w), resolved in world frame (unit vector)
  • v_0: Velocity of wheel center, resolved in world frame
  • w_0: Angular velocity of wheel, resolved in world frame
  • vContact_0: Velocity of contact point, resolved in world frame

Connector frames

  • frame_a: Frame for the wheel joint
source
Multibody.SphericalMethod
Spherical(; name, enforceState = false, isroot = true, w_rel_a_fixed = false, z_rel_a_fixed = false, sequence_angleStates, phi = 0, phi_d = 0, phi_dd = 0)

Joint with 3 constraints that define that the origin of frame_a and the origin of frame_b coincide. By default this joint defines only the 3 constraints without any potential state variables. If parameter enforceState is set to true, three states are introduced. The orientation of frame_b is computed by rotating frame_a along the axes defined in parameter vector sequence_angleStates (default = [1,2,3], i.e., the Cardan angle sequence) around the angles used as state. If angles are used as state there is the slight disadvantage that a singular configuration is present leading to a division by zero.

  • isroot: Indicate that frame_a is the root, otherwise frame_b is the root. Only relevant if enforceState = true.
  • sequence_angleStates: Rotation sequence
source

Components

The perhaps most fundamental component is a Body, this component has a single flange, frame_a, which is used to connect the body to other components. This component has a mass, a vector r_cm from frame_a to the center of mass, and a moment of inertia tensor I in the center of mass. The body can be thought of as a point mass with a moment of inertia tensor.

A mass with a shape can be modeled using a BodyShape. The primary difference between a Body and a BodyShape is that the latter has an additional flange, frame_b, which is used to connect the body to other components. The translation between flange_a and flange_b is determined by the vector r. The BodyShape is suitable to model, e.g., cylinders, rods, and boxes.

A rod without a mass (just a translation), is modeled using FixedTranslation.

Multibody.worldConstant

The world component is the root of all multibody models. It is a fixed frame with a parallel gravitational field and a gravity vector specified by the unit direction world.n (defaults to [0, -1, 0]) and magnitude world.g (defaults to 9.81).

source
Multibody.AccSensorMethod
AccSensor(;name)

Ideal sensor to measure the absolute flange angular acceleration

Connectors:

  • flange: Flange Flange of shaft from which sensor information shall be measured
  • a: RealOutput Absolute angular acceleration of flange
source
Multibody.AxisControlBusMethod
@connector AxisControlBus(; name)
  • motion_ref(t) = 0: = true, if reference motion is not in rest
  • angle_ref(t) = 0: Reference angle of axis flange
  • angle(t) = 0: Angle of axis flange
  • speed_ref(t) = 0: Reference speed of axis flange
  • speed(t) = 0: Speed of axis flange
  • acceleration_ref(t) = 0: Reference acceleration of axis flange
  • acceleration(t) = 0: Acceleration of axis flange
  • current_ref(t) = 0: Reference current of motor
  • current(t) = 0: Current of motor
  • motorAngle(t) = 0: Angle of motor flange
  • motorSpeed(t) = 0: Speed of motor flange
source
Multibody.BodyMethod
Body(; name, m = 1, r_cm, I = collect(0.001 * LinearAlgebra.I(3)), isroot = false, phi0 = zeros(3), phid0 = zeros(3), r_0=zeros(3))

Representing a body with 3 translational and 3 rotational degrees-of-freedom.

Parameters

  • m: Mass
  • r_cm: Vector from frame_a to center of mass, resolved in frame_a
  • I: Inertia matrix of the body
  • isroot: Indicate whether this component is the root of the system, useful when there are no joints in the model.
  • phi0: Initial orientation, only applicable if isroot = true
  • phid0: Initial angular velocity

Variables

  • r_0: Position vector from origin of world frame to origin of frame_a
  • v_0: Absolute velocity of frame_a, resolved in world frame (= D(r_0))
  • a_0: Absolute acceleration of frame_a resolved in world frame (= D(v_0))
source
Multibody.BodyShapeMethod
BodyShape(; name, m = 1, r, kwargs...)

The BodyShape component is similar to a Body, but it has two frames and a vector r that describes the translation between them, while the body has a single frame only.

  • r: Vector from frame_a to frame_b resolved in frame_a
  • All kwargs are passed to the internal Body component.
source
Multibody.FixedRotationMethod
FixedRotation(; name, r, n, sequence, isroot = false, angle, n_x, n_y)

Fixed translation followed by a fixed rotation of frame_b with respect to frame_a

  • r: Translation vector
  • n: Axis of rotation, resolved in frame_a
  • sequence: DESCRIPTION
  • angle: Angle of rotation around n, given in radians
source
Multibody.oriFunction
ori(frame, varw = false)

Get the orientation of sys as a RotationMatrix object.

For frames, the orientation is stored in the metadata field of the system as sys.metadata[:orientation].

If varw = true, the angular velocity variables w of the frame is also included in the RotationMatrix object, otherwise w is derived as the time derivative of R. varw = true is primarily used when selecting a component as root.

source

Forces

Multibody.DamperMethod
Damper(; d, name, kwargs)

Linear damper acting as line force between frame_a and frame_b. A force f is exerted on the origin of frame_b and with opposite sign on the origin of frame_a along the line from the origin of frame_a to the origin of frame_b according to the equation:

\[f = d D(s)\]

where d is the (viscous) damping parameter, s is the distance between the origin of frame_a and the origin of frame_b and D(s) is the time derivative of s.

Arguments:

  • d: Damping coefficient

See also SpringDamperParallel

source
Multibody.ForceMethod
Force(; name, resolveInFrame = :frame_b)

Force acting between two frames, defined by 3 input signals and resolved in frame world, frame_a, frame_b (default)

Connectors:

  • frame_a
  • frame_b
  • force: Of type Blocks.RealInput(3). x-, y-, z-coordinates of force resolved in frame defined by resolveInFrame.

Keyword arguments:

  • resolveInFrame: The frame in which the cut force and cut torque are resolved. Default is :frame_b, options include :frame_a and :world.
source
Multibody.SpringMethod
Spring(; c, name, m = 0, lengthFraction = 0.5, s_unstretched = 0, kwargs)

Linear spring acting as line force between frame_a and frame_b. A force f is exerted on the origin of frame_b and with opposite sign on the origin of frame_a along the line from the origin of frame_a to the origin of frame_b according to the equation:

\[f = c s\]

where c is the spring stiffness parameter, s is the distance between the origin of frame_a and the origin of frame_b.

Optionally, the mass of the spring is taken into account by a point mass located on the line between frame_a and frame_b (default: middle of the line). If the spring mass is zero, the additional equations to handle the mass are removed.

Arguments:

  • c: Spring stiffness
  • m: Mass of the spring (can be zero)
  • lengthFraction: Location of spring mass with respect to frame_a as a fraction of the distance from frame_a to frame_b (=0: at frame_a; =1: at frame_b)
  • s_unstretched: Length of the spring when it is unstretched
  • kwargs: are passed to LineForceWithMass

See also SpringDamperParallel

source
Multibody.SpringDamperParallelMethod
SpringDamperParallel(; name, c, d, s_unstretched)

Linear spring and linear damper in parallel acting as line force between frame_a and frame_b. A force f is exerted on the origin of frame_b and with opposite sign on the origin of frame_a along the line from the origin of frame_a to the origin of frame_b according to the equation:

\[f = c (s - s_{unstretched}) + d \cdot D(s)\]

where c, s_unstretched and d are parameters, s is the distance between the origin of frame_a and the origin of frame_b and D(s) is the time derivative of s.

source
Multibody.TorqueMethod
Torque(; name, resolveInFrame = :frame_b)

Torque acting between two frames, defined by 3 input signals and resolved in frame world, frame_a, frame_b (default)

Connectors:

  • frame_a
  • frame_b
  • torque: Of type Blocks.RealInput(3). x-, y-, z-coordinates of torque resolved in frame defined by resolveInFrame.

Keyword arguments:

  • resolveInFrame: The frame in which the cut force and cut torque are resolved. Default is :frame_b, options include :frame_a and :world.
source

Sensors

A sensor is an object that translates quantities in the mechanical domain into causal signals which can interact with causal components from ModelingToolkitStandardLibrary.Blocks, such as control systems etc.

Multibody.CutForceMethod
BasicCutForce(; name, resolveInFrame)

Basic sensor to measure cut force vector. Contains a connector of type Blocks.RealOutput with name force.

  • resolveInFrame: The frame in which the cut force and cut torque are resolved. Default is :frame_a, options include :frame_a and :world.
source
Multibody.CutTorqueMethod
CutTorque(; name, resolveInFrame)

Basic sensor to measure cut torque vector. Contains a connector of type Blocks.RealOutput with name torque.

  • resolveInFrame: The frame in which the cut force and cut torque are resolved. Default is :frame_a, options include :frame_a and :world.
source
Multibody.PartialCutForceBaseSensorMethod
PartialCutForceBaseSensor(; name, resolveInFrame = :frame_a)
  • resolveInFrame: The frame in which the cut force and cut torque are resolved. Default is :frame_a, options include :frame_a and :world.
source

Orientation utilities

Multibody.RotationMatrixType
RotationMatrix

A struct representing a 3D orientation as a rotation matrix.

If ODESystem is called on a RotationMatrix object o, symbolic variables for o.R and o.w are created and the value of o.R is used as the default value for the symbolic R.

Fields:

  • R::R3: The rotation 3×3 matrix ∈ SO(3)
  • w: The angular velocity vector
source
Multibody.NumRotationMatrixMethod
NumRotationMatrix(; R = collect(1.0 * I(3)), w = zeros(3), name, varw = false)

Create a new RotationMatrix struct with symbolic elements. R,w determine default values.

The primary difference between NumRotationMatrix and RotationMatrix is that the NumRotationMatrix constructor is used in the constructor of a Frame in order to introduce the frame variables, whereas RorationMatrix (the struct) only wraps existing variables.

  • varw: If true, w is a variable, otherwise it is derived from the derivative of R as w = get_w(R).
source
Multibody.absoluteRotationMethod
R2 = absoluteRotation(R1, R_rel)
  • R1: Orientation object to rotate frame 0 into frame 1
  • R_rel: Orientation object to rotate frame 1 into frame 2
  • R2: Orientation object to rotate frame 0 into frame 2
source
Multibody.axisRotationMethod
axisRotation(sequence, angle; name = :R)

Generate a rotation matrix for a rotation around the specified axis.

  • sequence: The axis to rotate around (1: x-axis, 2: y-axis, 3: z-axis)
  • angle: The angle of rotation (in radians)

Returns a RotationMatrix object.

source
Multibody.get_wMethod
get_w(R)

Compute the angular velocity w from the rotation matrix R and its derivative DR = D.(R).

source
Multibody.resolve1Method
h1 = resolve1(R21, h2)

R12 is a 3x3 matrix that transforms a vector from frame 1 to frame 2. h2 is a vector resolved in frame 2. h1 is the same vector in frame 1.

Typical usage:

resolve1(ori(frame_a), r_ab)
source
Multibody.resolve2Method
h2 = resolve2(R21, h1)

R21 is a 3x3 matrix that transforms a vector from frame 1 to frame 2. h1 is a vector resolved in frame 1. h2 is the same vector in frame 2.

Typical usage:

resolve2(ori(frame_a), a_0 - g_0)
source
Multibody.rotxFunction
rotx(t, deg = false)

Generate a rotation matrix for a rotation around the x-axis.

  • t: The angle of rotation (in radians, unless deg is set to true)
  • deg: (Optional) If true, the angle is in degrees

Returns a 3x3 rotation matrix.

source
Multibody.rotyFunction
roty(t, deg = false)

Generate a rotation matrix for a rotation around the y-axis.

  • t: The angle of rotation (in radians, unless deg is set to true)
  • deg: (Optional) If true, the angle is in degrees

Returns a 3x3 rotation matrix.

source
Multibody.rotzFunction
rotz(t, deg = false)

Generate a rotation matrix for a rotation around the z-axis.

  • t: The angle of rotation (in radians, unless deg is set to true)
  • deg: (Optional) If true, the angle is in degrees

Returns a 3x3 rotation matrix.

source

Interfaces