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 thant
to not conflict with the often used independent variablet
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 functionori
.
Index
Multibody.world
Multibody.Body
Multibody.BodyShape
Multibody.CutForce
Multibody.CutTorque
Multibody.Damper
Multibody.FixedRotation
Multibody.FixedTranslation
Multibody.Force
Multibody.Frame
Multibody.FreeMotion
Multibody.GearConstraint
Multibody.PartialCutForceBaseSensor
Multibody.Prismatic
Multibody.Revolute
Multibody.RollingWheel
Multibody.RollingWheelJoint
Multibody.Spherical
Multibody.Spring
Multibody.Torque
Multibody.absoluteRotation
Multibody.axisRotation
Multibody.gravity_acceleration
Multibody.resolve1
Multibody.resolve2
Multibody.rotx
Multibody.roty
Multibody.rotz
Frames
Multibody.Frame
— FunctionFrame(; 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 framef
: The cut force resolved in the connector frametau
: The cut torque resolved in the connector frame- Depending on usage, also rotation and rotational velocity variables.
Joints
Multibody.FreeMotion
— MethodFreeMotion(; name, enforceStates = 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 states.
Note, that bodies such as Body
, BodyShape
, have potential states 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 states of the FreeMotion object are:
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
enforceStates
: Enforce this joint having states, this is often desired and is the default choice.sequence
: Rotation sequencew_rel_a_fixed
: = true, ifw_rel_a_start
are used as initial values, else as guess valuesz_rel_a_fixed
: = true, ifz_rel_a_start
are used as initial values, else as guess values
Initial codition arguments:
phi
phi_d
phi_dd
w_rel_b
r_rel_a
v_rel_a
a_rel_a
Multibody.GearConstraint
— MethodGearConstraint(; 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 ration_a
: Axis of rotation offrame_a
n_b
: Axis of rotation offrame_b
r_a
: Vector from framebearing
toframe_a
resolved in bearingr_b
: Vector from framebearing
toframe_b
resolved in bearing
Multibody.Prismatic
— MethodPrismatic(; 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
andsupport
, 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 jointsupport
: 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.
Multibody.Revolute
— MethodRevolute(; name, phi0 = 0, w0 = 0, n, useAxisFlange = false)
Revolute joint with 1 rotational degree-of-freedom
phi0
: Initial anglew0
: Iniitial angular velocityn
: The axis of rotationuseAxisFlange
: If true, the joint will have two additional frames from Mechanical.Rotational,axis
andsupport
, 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 jointsupport
: 1-dim. rotational flange of the drive support (assumed to be fixed in the world frame, NOT in the joint)
Multibody.RollingWheel
— MethodRollingWheel(; 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 componentradius
: Radius of the wheelm
: Mass of the wheelI_axis
: Moment of inertia of the wheel along its axisI_long
: Moment of inertia of the wheel perpendicular to its axiswidth
: Width of the wheel (default: 0.035)x0
: Initial x-position of the wheel axisy0
: Initial y-position of the wheel axiskwargs...
: Additional keyword arguments passed to theRollingWheelJoint
function
Variables:
x
: x-position of the wheel axisy
: y-position of the wheel axisangles
: Angles to rotate world-frame intoframe_a
around z-, y-, x-axisder_angles
: Derivatives of angles
Named components:
frame_a
: Frame for the wheel componentrollingWheel
: Rolling wheel joint representing the wheel's contact with the road surface
Multibody.RollingWheelJoint
— MethodRollingWheelJoint(; 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 axisy
: y-position of the wheel axisz
: z-position of the wheel axisangles
: Angles to rotate world-frame intoframe_a
around z-, y-, x-axisder_angles
: Derivatives of anglesr_road_0
: Position vector from world frame to contact point on road, resolved in world framef_wheel_0
: Force vector on wheel, resolved in world framef_n
: Contact force acting on wheel in normal directionf_lat
: Contact force acting on wheel in lateral directionf_long
: Contact force acting on wheel in longitudinal directionerr
: 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 framedelta_0
: Distance vector from wheel center to contact pointe_n_0
: Unit vector in normal direction of road at contact point, resolved in world framee_lat_0
: Unit vector in lateral direction of road at contact point, resolved in world framee_long_0
: Unit vector in longitudinal direction of road at contact point, resolved in world frames
: Road surface parameter 1w
: Road surface parameter 2e_s_0
: Road heading at(s,w)
, resolved in world frame (unit vector)v_0
: Velocity of wheel center, resolved in world framew_0
: Angular velocity of wheel, resolved in world framevContact_0
: Velocity of contact point, resolved in world frame
Connector frames
frame_a
: Frame for the wheel joint
Multibody.Spherical
— MethodSpherical(; name, enforceStates = 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 states. If parameter enforceStates
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 states. If angles are used as states there is the slight disadvantage that a singular configuration is present leading to a division by zero.
isroot
: Indicate thatframe_a
is the root, otherwiseframe_b
is the root. Only relevant ifenforceStates = true
.sequence_angleStates
: Rotation sequence
Components
Multibody.world
— ConstantThe 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).
Multibody.Body
— MethodBody(; 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.
m
: Massr_cm
: Vector fromframe_a
to center of mass, resolved inframe_a
I
: Inertia matrix of the bodyisroot
: Indicate whether this component is the root of the system, useful when there are no joints in the model.phi0
: Initial orientation, only applicable ifisroot = true
phid0
: Initial angular velocity
Multibody.BodyShape
— MethodBodyShape(; 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 fromframe_a
toframe_b
resolved inframe_a
- All
kwargs
are passed to the internalBody
component.
Multibody.FixedRotation
— MethodFixedRotation(; 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 vectorn
: Axis of rotation, resolved in frame_asequence
: DESCRIPTIONangle
: Angle of rotation aroundn
, given in radians
Multibody.FixedTranslation
— MethodFixedTranslation(; name, r)
Fixed translation of frame_b
with respect to frame_a
with position vector r
resolved in frame_a
.
Can be though of as a massless rod. For a massive rod, see BodyShape
or BodyCylinder
.
Multibody.gravity_acceleration
— MethodCompute the gravity acceleration, resolved in world frame
Forces
Multibody.Damper
— MethodDamper(; 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
Multibody.Force
— MethodForce(; 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 typeBlocks.RealInput(3)
. x-, y-, z-coordinates of force resolved in frame defined byresolveInFrame
.
Multibody.Spring
— MethodSpring(; 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 stiffnessm
: Mass of the spring (can be zero)lengthFraction
: Location of spring mass with respect toframe_a
as a fraction of the distance fromframe_a
toframe_b
(=0: atframe_a
; =1: atframe_b
)s_unstretched
: Length of the spring when it is unstretchedkwargs
: are passed toLineForceWithMass
Multibody.Torque
— MethodTorque(; 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 typeBlocks.RealInput(3)
. x-, y-, z-coordinates of torque resolved in frame defined byresolveInFrame
.
Sensors
Multibody.CutForce
— MethodBasicCutForce(; 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
.
Multibody.CutTorque
— MethodCutTorque(; 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
.
Multibody.PartialCutForceBaseSensor
— MethodPartialCutForceBaseSensor(; 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
.
Orientation utilities
Multibody.absoluteRotation
— MethodR2 = absoluteRotation(R1, R_rel)
R1
:Orientation
object to rotate frame 0 into frame 1R_rel
:Orientation
object to rotate frame 1 into frame 2R2
:Orientation
object to rotate frame 0 into frame 2
Multibody.axisRotation
— MethodaxisRotation(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.
Multibody.resolve1
— Methodh1 = 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)
Multibody.resolve2
— Methodh2 = 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)
Multibody.rotx
— Functionrotx(t, deg = false)
Generate a rotation matrix for a rotation around the x-axis.
t
: The angle of rotation (in radians, unlessdeg
is set to true)deg
: (Optional) If true, the angle is in degrees
Returns a 3x3 rotation matrix.
Multibody.roty
— Functionroty(t, deg = false)
Generate a rotation matrix for a rotation around the y-axis.
t
: The angle of rotation (in radians, unlessdeg
is set to true)deg
: (Optional) If true, the angle is in degrees
Returns a 3x3 rotation matrix.
Multibody.rotz
— Functionrotz(t, deg = false)
Generate a rotation matrix for a rotation around the z-axis.
t
: The angle of rotation (in radians, unlessdeg
is set to true)deg
: (Optional) If true, the angle is in degrees
Returns a 3x3 rotation matrix.