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.BodyBoxConstant
BodyBox(; name, m = 1, r = [1, 0, 0], r_shape = [0, 0, 0], width_dir = [0,1,0])

Rigid body with box shape. The mass properties of the body (mass, center of mass, inertia tensor) are computed from the box data. Optionally, the box may be hollow. The (outer) box shape is used in the animation, the hollow part is not shown in the animation. The two connector frames frame_a and frame_b are always parallel to each other.

Parameters

  • r: (structural parameter) Vector from frame_a to frame_b resolved in frame_a
  • r_shape: (structural parameter) Vector from frame_a to box origin, resolved in frame_a
  • width_dir: (structural parameter) Vector in width direction of box, resolved in frame_a
  • length_dir: (structural parameter) Vector in length direction of box, resolved in frame_a
  • length: (structural parameter) Length of box
  • width = 0.3length: Width of box
  • height = width: Height of box
  • inner_width: Width of inner box surface (0 <= inner_width <= width)
  • inner_height: Height of inner box surface (0 <= inner_height <= height)
  • density = 7700: Density of cylinder (e.g., steel: 7700 .. 7900, wood : 400 .. 800)
  • color: Color of box in animations
source
Multibody.BodyCylinderConstant
BodyCylinder(; name, m = 1, r = [0.1, 0, 0], r_shape = [0, 0, 0], dir = r - r_shape, length = _norm(r - r_shape), diameter = 1, inner_diameter = 0, density = 7700, color = purple)

Rigid body with cylinder shape. The mass properties of the body (mass, center of mass, inertia tensor) are computed from the cylinder data. Optionally, the cylinder may be hollow. The two connector frames frame_a and frame_b are always parallel to each other.

Parameters

  • r: (Structural parameter) Vector from frame_a to frame_b resolved in frame_a
  • r_shape: (Structural parameter) Vector from frame_a to cylinder origin, resolved in frame_a
  • dir: Vector in length direction of cylinder, resolved in frame_a
  • length: Length of cylinder
  • diameter: Diameter of cylinder
  • inner_diameter: Inner diameter of cylinder (0 <= inner_diameter <= diameter)
  • density: Density of cylinder kg/m³
  • color: Color of cylinder in animations

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.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.80665).

source
Multibody.AccSensorMethod
AccSensor(;name)

Ideal rotational 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, isroot = false, phi0 = zeros(3), phid0 = zeros(3), r_0 = zeros(3), state_priority = 2, quat = false, sparse_I = false)

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

This component has a single frame, frame_a. To represent bodies with more than one frame, see BodyShape, BodyCylinder, BodyBox. The inertia tensor is defined with respect to a coordinate system that is parallel to frame_a with the origin at the center of mass of the body.

Performance optimization

  • sparse_I: If true, the zero elements of the inerita matrix are considered "structurally zero", and this fact is used to optimize performance. When this option is enabled, the elements of the inertia matrix that were zero when the component was created cannot changed without reinstantiating the component. This performance optimization may be useful, e.g., when the inertia matrix is known to be diagonal.

Parameters

  • m: Mass
  • r_cm: Vector from frame_a to center of mass, resolved in frame_a
  • I_11, I_22, I_33, I_21, I_31, I_32: Inertia-matrix elements
  • 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 and quat = false
  • 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))

Rendering options

  • radius: Radius of the joint in animations
  • cylinder_radius: Radius of the cylinder from frame to COM in animations (only drawn if r_cm is non-zero). Defaults to radius/2
  • color: Color of the joint in animations, a vector of length 4 with values between [0, 1] providing RGBA values
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.
  • shapefile: A path::String to a CAD model that can be imported by MeshIO for 3D rendering. If none is provided, a cylinder shape is rendered.

See also BodyCylinder and BodyBox for body components with predefined shapes and automatically computed inertial properties based on geometry and density.

source
Multibody.FixedMethod
Fixed(; name, r = [0, 0, 0], render = true)

A component rigidly attached to the world frame with translation r between the world and the frame_b. The position vector r is resolved in the world frame.

source
Multibody.FixedRotationMethod
FixedRotation(; name, r, n, sequence, isroot = false, angle)

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
  • angle: Angle of rotation around n, given in radians

To obtain an axis-angle representation of any rotation, see Conversion between orientation formats

source
Multibody.PoseMethod
Pose(; name, r = [0, 0, 0], R, q, render = true)

Forced movement of a flange according to a reference position r and reference orientation R. The reference arrays r and R are resolved in the world frame, and may be any symbolic expression. As an alternative to specifying R, it is possible to specify a quaternion q (4-vector quaternion with real part first).

Example usage:

using Multibody.Rotations
R = RotXYZ(0, 0.5sin(t), 0)
@named rot = Multibody.Pose(; r=[sin(t), 0, 0], R)

Connectors

  • frame_b: The frame that is forced to move according to the reference position and orientation.

Arguments

  • r: Position vector from world frame to frame_b, resolved in world frame
  • R: Reference orientation matrix
  • q: Reference quaternion (optional alternative to R)
  • render: Render the component in animations
  • normalize: If a quaternion is provided, normalize the quaternion (default = true)
  • x_locked, y_locked, z_locked: Lock the translation in the x, y, and z directions, respectively. This allows for selective specification of the translation components, i.e., if y_locked = false, the y-component of the translation is not constrained to follow r.

See also Position for a component that allows for only forced translation.

source
Multibody.PositionMethod
Position(; name, r = [0, 0, 0], render = true, fixed_orientation = true)

Forced movement of a flange according to a reference position r. Similar to Fixed, but r is not a parameter, and may thus be any time-varying symbolic expression. The reference position vector r is resolved in the world frame. Example: r = [sin(t), 0, 0].

Arguments:

  • r: Position vector from world frame to frame_b, resolved in world frame
  • render: Render the component in animations
  • fixed_orientation: If true, the orientation of the frame is fixed to the world frame. If false, the orientation is free to change.

See also Pose for a component that allows for forced orientation as well.

source
Multibody.RopeMethod
Rope(; name, l = 1, n = 10, m = 1, c = 0, d = 0, kwargs)

Model a rope (string / cable) of length l and mass m.

The rope is modeled as a series of n links, each connected by a Spherical joint. The links are either fixed in length (default, modeled using BodyShape) or flexible, in which case they are modeled as a Translational.Spring and Translational.Damper in parallel with a Prismatic joint with a Body adding mass to the center of the link segment. The flexibility is controlled by the parameters c and d, which are the stiffness and damping coefficients of the spring and damper, respectively. The default values are c = 0 and d = 0, which corresponds to a stiff rope.

  • l: Unstretched length of rope
  • n: Number of links used to model the rope. For accurate approximations to continuously flexible ropes, a large number may be required.
  • m: The total mass of the rope. Each rope segment will have mass m / n.
  • c: The equivalent stiffness of the rope, i.e., the rope will act like a spring with stiffness c.
  • d: The equivalent damping in the stretching direction of the rope, i.e., the taught rope will act like a damper with damping d.
  • d_joint: Viscous damping in the joints between the links. A positive value makes the rope dissipate energy while flexing (as opposed to the damping d which dissipats energy due to stretching).
  • dir: A vector of norm 1 indicating the initial direction of the rope.

Damping

There are three different methods of adding damping to the rope:

  • Damping in the stretching direction of the rope, controlled by the parameter d.
  • Damping in flexing of the rope, modeled as viscous friction in the joints between the links, controlled by the parameter d_joint.
  • Air resistance to the rope moving through the air, controlled by the parameter air_resistance. This damping is quadratic in the velocity ($f_d ~ -||v||v$) of each link relative to the world frame.

Rendering

  • color = [255, 219, 120, 255]./255
  • radius = 0.05f0
  • jointradius=0
  • jointcolor=color
source
Multibody.WorldMethod
World(; name, render=true, point_gravity=false, n = [0.0, -1.0, 0.0], g=9.80665, mu=3.986004418e14)

All multibody models must include exactly one world component defined at the top level. The frame_b of the world is fixed in the origin.

If a connection to the world is needed in a component model, use Fixed instead.

Arguments

  • name: Name of the world component
  • render: Render the component in animations
  • point_gravity: If true, the gravity is always opinting towards a single point in space. If false, the gravity is always pointing in the same direction n.
  • n: Gravity direction unit vector, defaults to [0, -1, 0], only applicable if point_gravity = false
  • g: Gravitational acceleration, defaults to 9.80665
  • mu: Gravity field constant, defaults to 3.986004418e14, only applicable to point gravity
source
Multibody.oriFunction
ori(frame, varw = false)

Get the orientation of sys as a RotationMatrix object. See also get_rot. ori(frame).R is the rotation matrix that rotates a vector from the world coordinate system to the local frame.

For frames, the orientation is stored in the metadata field of the system as get_metadata(sys)[: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
Multibody.RollingConstraintVerticalWheelMethod
RollingConstraintVerticalWheel(;
    name,
    radius = 0.3,
    lateral_sliding_constraint = true,
)

Rolling constraint for wheel that is always perpendicular to x-z plane

Joint for a wheel rolling on the x-z plane of the world frame intended for an idealized wheelset. To meet this objective, the wheel always runs upright and enables no slip in the longitudinal direction of the wheel/ground contact. On the contrary, the wheel can optionally slip in the lateral direction which is reasonable for the wheelset where just one of the wheels should be laterally constrained. 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. A wheel body collecting the mass and inertia

Arguments and parameters:

  • name: Name of the rolling wheel joint component
  • radius: Wheel radius
  • lateral_sliding_constraint: true, if lateral sliding constraint taken into account, = false if lateral force = 0 (needed to avoid overconstraining if two ideal rolling wheels are connect on one axis)

Connectors:

  • frame_a: Frame for the wheel joint
source
Multibody.RollingWheelMethod
RollingWheel(; name, radius, m, I_axis, I_long, width=0.035, x0, y0, kwargs...)

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

A wheel rolling on the x-z 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. A Revolute joint rotationg around n = [0, 1, 0] is required to attach the wheel to a wheel axis.

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
  • z0: Initial z-position of the wheel axis
  • kwargs...: Additional keyword arguments passed to the RollingWheelJoint function

Variables:

  • x: x-position of the wheel axis
  • z: z-position of the wheel axis
  • angles: Angles to rotate world-frame into frame_a around y-, z-, x-axis
  • der_angles: Derivatives of angles (y: like rotational velocity of a spinning coin, z: wheel forward spin speed, x: wheel falling over speed)

Named components:

  • frame_a: Frame for the wheel component
  • wheeljoint: Rolling wheel joint representing the wheel's contact with the road surface
Rendering tip

Due to the symmetry of the wheel, it can be hard to discern how the wheel is rotating in animations. Try enabling rendering of the frame of the wheel by setting

wheel.frame_a.render => true;
wheel.frame_a.length => 1.1radius;
wheel.frame_a.radius => 0.02radius;
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 y=0). See RollingWheel for a realistic wheel model with inertia.

A joint for a wheel rolling on the x-z 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 z-axis of frame_a is identical with the wheel spin axis, i.e. the wheel rotates about z-axis of frame_a. A wheel body collecting the mass and inertia should be connected to this frame.

Arguments and parameters:

  • radius: Radius of the wheel
  • angles: Angles to rotate world-frame into frame_a around y-, z-, x-axis
  • surface: By default, the wheel is rolling on a flat xz plane. A function surface = (x, z)->y may be provided to define a road surface. The function should return the height of the road at (x, z).

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 y-, z-, 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.RollingWheelSetMethod
RollingWheelSet(;
    name,
    radius = 0.3,
    m_wheel = 1.0,
    I_axis = 1.0,
    I_long = 1.0,
    track = 1.0,
    state_priority = 1,
    x0 = 0,
    z0 = 0,
    phi0 = 0,
    theta1_0 = 0,
    theta2_0 = 0,
    der_theta1_0 = 0,
    der_theta2_0 = 0,
    width_wheel = 0.01,
    color = [0.3, 0.3, 0.3, 1],
    render = true,
    iscut = false,
)

Ideal rolling wheel set consisting of two ideal rolling wheels connected together by an axis

Two wheels are connected by an axis and can rotate around this axis. The wheels are rolling on the x-z plane of the world frame. The coordinate system attached to the center of the wheel axis (frame_middle) is constrained so that it is always parallel to the x-z plane. If all generalized coordinates are zero, frame_middle is parallel to the world frame.

Arguments and parameters:

  • iscut: if more than one wheel set is connected to the same rigid body, iscut must be set to true for all but one set. This avoids overconstraining the system by replacing the planar joint giving the set coordinates by an unconstrained FreeMotion joint.
  • radius: Radius of one wheel
  • m_wheel: Mass of one wheel
  • I_axis: Moment of inertia of one wheel around its rotation axis
  • I_long: Moment of inertia of one wheel perpendicular to its rotation axis
  • track: Distance between the two wheels (= axle track)

Connectors

  • frame_middle: Frame fixed in middle of axis connecting both wheels (z-axis: along wheel axis, y-axis: upwards)
  • frame1: Frame fixed in center point of left wheel, rotating with the wheel (z-axis: along wheel axis, y-axis: upwards when wheel angle is zero)
  • frame2: Frame fixed in center point of right wheel, rotating with the wheel (z-axis: along wheel axis, y-axis: upwards when wheel angle is zero)
  • axis1: 1-dim. Rotational flange that drives the left wheel
  • axis2: 1-dim. Rotational flange that drives the right wheel
  • support: Support of 1D axes

To connect driving torques or friction to rotation of the wheels, connect between axis1 and support, and axis2 and support respectively. To connect the wheel set to, e.g., a body, connect the frame_middle to the body frame.

source
Multibody.RollingWheelSetJointMethod
RollingWheelSetJoint(;
    name,
    radius = 0.3,
    track = 1.0,
    state_priority = 1,
    x0 = 0,
    z0 = 0,
    phi0 = 0,
    theta1_0 = 0,
    theta2_0 = 0,
    der_theta1_0 = 0,
    der_theta2_0 = 0,
    render = true,
    iscut = false,
)

Joint (no mass, no inertia) that describes an ideal rolling wheel set (two ideal rolling wheels connected together by an axis)

An assembly joint for a wheelset rolling on the x-z plane of the world frame. The frames frame1 and frame2 are connected to rotating wheels; the frame_middle moves in a plane parallel to the x-z plane of the world and should be connected to the vehicle body.

To work properly, the gravity acceleration vector g of the world must point in the negative y-axis (default)

Arguments and parameters:

  • iscut: if more than one wheel set is connected to the same rigid body, iscut must be set to true for all but one set. This avoids overconstraining the system by replacing the planar joint giving the set coordinates by an unconstrained FreeMotion joint.
  • radius: Radius of one wheel
  • track: Distance between the two wheels (= axle track)

Connectors:

  • frame_middle: Frame fixed in middle of axis connecting both wheels (z-axis: along wheel axis, y-axis: upwards)
  • frame1: Frame fixed in center point of left wheel, rotating with the wheel (z-axis: along wheel axis, y-axis: upwards when wheel angle is zero)
  • frame2: Frame fixed in center point of right wheel, rotating with the wheel (z-axis: along wheel axis, y-axis: upwards when wheel angle is zero)
  • axis1: 1-dim. Rotational flange that drives the joint
  • axis2: 1-dim. Rotational flange that drives the joint
  • support: Support of 1-dim axes
source
Multibody.SlipWheelJointMethod
SlipWheelJoint(; name, radius, angles = zeros(3), der_angles = zeros(3), x0 = 0, y0 = radius, z0 = 0, sequence, iscut = false, surface = nothing, vAdhesion_min = 0.1, vSlide_min = 0.1, sAdhesion = 0.04, sSlide = 0.12, mu_A = 0.8, mu_S = 0.6, phi_roll = 0, w_roll = 0)

Joint for a wheel with slip rolling on a surface. See https://people.inf.ethz.ch/fcellier/MS/andres_ms.pdf for details.

Integrator choice

The slip model contains a discontinuity in the second derivative at the transitions between adhesion and sliding. This can cause problems for integrators, in particular BDF-type integrators.

Normal force

The wheel cannot leave the ground. Make sure that the normal force f_n never becomes negative.

Parameters

  • radius: Radius of the wheel
  • vAdhesion_min: Minimum velocity for the peak of the adhesion curve (regularization close to 0)
  • vSlide_min: Minimum velocity for the start of the flat region of the slip curve (regularization close to 0)
  • sAdhesion: Adhesion slippage. The peak of the adhesion curve appears when the wheel slip is equal to sAdhesion.
  • sSlide: Sliding slippage. The flat region of the adhesion curve appears when the wheel slip is greater than sSlide.
  • mu_A: Friction coefficient at adhesion
  • mu_S: Friction coefficient at sliding
  • surface: By default, the wheel is rolling on a flat xz plane. A function surface = (x, z)->y may be provided to define a road surface. The function should return the height of the road at (x, z). Note: if a function that depends on parameters is provided, make sure the parameters are scoped appropriately using, e.g., ParentScope.
  • state: (structural) whether or not the component has angular state variables. Default is true.

State and iscut

When the wheel is mounted on an axis that is rooted, one may either supply state=false or iscut = true. With state = false, the angular state variables are not included in the wheel and there is thus no kinematic chain introduced. This reduces the total number of variables in the system. if the angular variables are required, one may instead pass iscut=true to cut the kinematic loop that is introduced when coupling the angles of the wheel to the orientation of the frame_a, unless this is cut elsewhere.

Understaning the slip model

The following Julia code draws the slip model with descriptive labels

using Plots
vAdhesion = 0.2
vSlide = 0.4
mu_A = 0.95
mu_S = 0.7
v = range(0, stop=1, length=500) # Simulating the slip velocity
μ = Multibody.PlanarMechanics.limit_S_triple.(vAdhesion, vSlide, mu_A, mu_S, v)
plot(v, μ, label=nothing, lw=2, color=:black, xlabel = "$v_{Slip}$", ylabel = "$\mu$")
scatter!([vAdhesion, vSlide], [mu_A, mu_S], color=:white, markerstrokecolor=:black)
hline!([mu_A, mu_S], linestyle=:dash, color=:black, alpha=0.5)
vline!([vAdhesion, vSlide], linestyle=:dash, color=:black, alpha=0.5)
plot!(
    xticks = ((vAdhesion, vSlide), ["$v_{Adhesion}$", "$v_{Slide}$"]),
    yticks = ((mu_A, mu_S), ["$\mu_{adhesion}$", "$\mu_{slide}$"]),
    framestyle = :zerolines,
    legend = false,
)
source
Multibody.SlippingWheelMethod
SlippingWheel(; name, radius, m, I_axis, I_long, width = 0.035, x0=0, z0=0,
                  angles = zeros(3), der_angles = zeros(3), kwargs...)

Wheel with slip rolling on a surface.

Parameters

  • 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 (for rendering)
  • x0: Initial x-position of the wheel axis
  • z0: Initial z-position of the wheel axis
  • state: (structural) whether or not the component has angular state variables.

Variables

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

Connectors

  • frame_a: Frame for the wheel component

Examples

See Docs: Wheels

source
Multibody.PlanarMechanics.BodyShapeConstant
BodyShape(; name, r = [1,0], r_cm = 0.5*r, gy = -9.80665)

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.

Parameters

  • r: (Structural) Vector from frame_a to frame_b resolved in frame_a
  • r_cm: (Structural) Vector from frame_a to the center of mass resolved in frame_a

Subsystems

  • translation: FixedTranslation Fixed translation between frame_a and frame_b
  • translation_cm: FixedTranslation Fixed translation between frame_a and the center of mass
  • body: Body Body component placed at center of mass. This component holds the inertial properties

Connectors

  • frame_a
  • frame_b
source
Multibody.PlanarMechanics.DamperConstant
Damper(; name, d = 1, s_small = 1.e-10)

Linear (velocity dependent) damper

Parameters:

  • d: [N.s/m] Damping constant
  • s_small: [m] Prevent zero-division if distance between framea and frameb is zero

Connectors:

  • frame_a Frame Coordinate system fixed to the component with one cut-force and cut-torque
  • frame_b Frame Coordinate system fixed to the component with one cut-force and cut-torque
source
Multibody.PlanarMechanics.DifferentialGearConstant
DifferentialGear(; name)

A 1D-rotational component that is a variant of a planetary gear and can be used to distribute the torque equally among the wheels on one axis.

Connectors:

  • flange_b (Rotational.Flange) Flange for the input torque
  • flange_left (Rotational.Flange) Flange for the left output torque
  • flange_right (Rotational.Flange) Flange for the right output torque
source
Multibody.PlanarMechanics.FixedConstant
Fixed(; name, r = [0.0, 0.0], phi = 0.0)

Frame fixed in the planar world frame at a given position and orientation

Parameters:

  • r: [m, m] Fixed absolute x,y-position, resolved in world frame
  • phi: [rad] Fixed angle

Connectors:

  • frame_b: 2-dim. Coordinate system
source
Multibody.PlanarMechanics.FixedTranslationConstant
FixedTranslation(; name, r::AbstractArray, l)

A fixed translation between two components (rigid rod)

Parameters:

  • rx: [m] Fixed x-length of the rod resolved w.r.t to body frame_a at phi = 0
  • ry: [m] Fixed y-length of the rod resolved w.r.t to body frame_a at phi = 0
  • radius: [m] Radius of the rod in animations
  • render: [Bool] Render the rod in animations

Connectors:

  • frame_a Frame Coordinate system fixed to the component with one cut-force and cut-torque
  • frame_b Frame Coordinate system fixed to the component with one cut-force and cut-torque
source
Multibody.PlanarMechanics.IdealPlanetaryConstant
IdealPlanetary(; name, ratio = 2)

The IdealPlanetary gear box is an ideal gear without inertia, elasticity, damping or backlash consisting of an inner sun wheel, an outer ring wheel and a planet wheel located between sun and ring wheel. The bearing of the planet wheel shaft is fixed in the planet carrier. The component can be connected to other elements at the sun, ring and/or carrier flanges. It is not possible to connect to the planet wheel. If inertia shall not be neglected, the sun, ring and carrier inertias can be easily added by attaching inertias (= model Inertia) to the corresponding connectors. The inertias of the planet wheels are always neglected.

The ideal planetary gearbox is uniquely defined by the ratio of the number of ring teeth $z_r$ with respect to the number of sun teeth $z_s$. For example, if there are 100 ring teeth and 50 sun teeth then ratio = $z_r/z_s = 2$. The number of planet teeth $z_p$ has to fulfill the following relationship:

\[z_p = (z_r - z_s) / 2\]

Therefore, in the above example $z_p = 25$ is required.

According to the overall convention, the positive direction of all vectors, especially the absolute angular velocities and cut-torques in the flanges, are along the axis vector displayed in the icon.

Parameters:

  • ratio: Number of ring teeth/sun teeth

Connectors:

  • sun (Rotational.Flange) Sun wheel
  • carrier (Rotational.Flange) Planet carrier
  • ring (Rotational.Flange) Ring wheel
source
Multibody.PlanarMechanics.SimpleWheelConstant
SimpleWheel(; name, radius = 0.3, color = [1, 0, 0, 1], μ = 1e9)

Simple wheel model with viscous lateral friction and a driving torque

Connectors:

  • frame_a (Frame) Coordinate system fixed to the component with one cut-force and cut-torque
  • thrust (RealInput) Input for the longitudinal force applied to the wheel

Parameters:

  • μ: [Ns/m] Viscous friction coefficient
  • radius: [m] Radius of the wheel
  • color: Color of the wheel in animations

Variables:

  • θ: [rad] Wheel angle
  • Vx: [m/s] Longitudinal velocity (resolved in local frame)
  • Vy: [m/s] Lateral velocity (resolved in local frame)
  • Fy: [N] Lateral friction force
  • Fx: [N] Applied longitudinal wheel force
source
Multibody.PlanarMechanics.SpringConstant
Spring(; name, c_x = 1, c_y = 1, c_phi = 1e5, s_relx0 = 0, s_rely0 = 0, phi_rel0 = 0, s_small = 1.e-10)

Linear 2D translational spring

Parameters:

  • c_x: [N/m] Spring constant in x dir
  • c_y: [N/m] Spring constant in y dir
  • c_phi: [N.m/rad] Spring constant in phi dir
  • s_relx0: [m] Unstretched spring length
  • s_rely0: [m] Unstretched spring length
  • phi_rel0: [rad] Unstretched spring angle
  • s_small: [m] Prevent zero-division if distance between framea and frameb is zero
  • num_windings: [Int] Number of windings of the coil when rendered
  • color = [0,0,1,1] Color of the spring in animations
  • render = true Render the spring in animations
  • radius = 0.1 Radius of spring when rendered
  • N = 200 Number of points in mesh when rendered

Connectors:

  • frame_a Frame Coordinate system fixed to the component with one cut-force and cut-torque
  • frame_b Frame Coordinate system fixed to the component with one cut-force and cut-torque
source
Multibody.PlanarMechanics.SpringDamperConstant
SpringDamper(; name, c_x = 1, c_y = 1, c_phi = 1e5, d_x = 1, d_y = 1, d_phi = 1, s_relx0 = 0, s_rely0 = 0, phi_rel0 = 0, s_small = 1.e-10)

Linear 2D translational spring damper model

Parameters:

  • c_x: [N/m] Spring constant in x dir
  • c_y: [N/m] Spring constant in y dir
  • c_phi: [N.m/rad] Spring constant in phi dir
  • d_x: [N.s/m] Damping constant in x dir
  • d_y: [N.s/m] Damping constant in y dir
  • d_phi: [N.m.s/rad] Damping constant in phi dir
  • s_relx0: [m] Unstretched spring length
  • s_rely0: [m] Unstretched spring length
  • phi_rel0: [rad] Unstretched spring angle
  • s_small: [m] Prevent zero-division if distance between framea and frameb is zero
  • num_windings: [Int] Number of windings of the coil when rendered
  • color = [0,0,1,1] Color of the spring in animations
  • render = true Render the spring in animations
  • radius = 0.1 Radius of spring when rendered
  • N = 200 Number of points in mesh when rendered

Connectors:

  • frame_a Frame Coordinate system fixed to the component with one cut-force and cut-torque
  • frame_b Frame Coordinate system fixed to the component with one cut-force and cut-torque
source
Multibody.PlanarMechanics.BodyMethod
Body(; name, m=1, I=0.1, r=0, gy=-9.80665, radius=0.1, render=true, color=Multibody.purple)

Body component with mass and inertia

Parameters:

  • m: [kg] mass of the body
  • I: [kg.m²] inertia of the body with respect to the origin of frame along the z-axis of frame
  • r: [m, m] Translational position x,y-position
  • gy: [m/s²] gravity field acting on the mass in the y-direction, positive value acts in the positive direction defaults to -9.80665
  • radius: [m] Radius of the body in animations
  • render: [Bool] Render the body in animations
  • color: [Array{Float64,1}] Color of the body in animations

Variables:

  • r: [m, m] x,y position
  • v: [m/s, m/s] x,y velocity
  • a: [m/s², m/s²] x,y acceleration
  • phi: [rad] rotation angle (counterclockwise)
  • w: [rad/s] angular velocity
  • α: [rad/s²] angular acceleration

Connectors:

  • frame: 2-dim. Coordinate system
source
Multibody.PlanarMechanics.SlipBasedWheelJointMethod
SlipBasedWheelJoint(;
    name,
    r = [1, 0],
    N,
    vAdhesion_min,
    vSlide_min,
    sAdhesion,
    sSlide,
    mu_A,
    mu_S,
    render = true,
    color = [0.1, 0.1, 0.1, 1],
    z = 0,
    diameter = 0.1,
    width = diameter * 0.6,
    radius = 0.1,
    w_roll = nothing,
)

Slip-based wheel joint

The ideal wheel joint models the behavior of a wheel rolling on a x,y-plane whose contact patch has slip-dependent friction characteristics. This is an approximation for wheels with a rim and a rubber tire.

The force depends with friction characteristics on the slip. The slip is split into two components:

  • lateral slip: the lateral velocity divided by the rolling velocity.
  • longitudinal slip: the longitudinal slip velocity divided by the rolling velocity.

For low rolling velocity this definition become ill-conditioned. Hence a dry-friction model is used for low rolling velocities. For zero rolling velocity, the intitialization might fail if automatic differentiation is used. Either start with a non-zero (but tiny) rolling velocity or pass autodiff=false to the solver.

The radius of the wheel can be specified by the parameter radius. The driving direction (for phi = 0) can be specified by the parameter r. The normal load is set by N.

The wheel contains a 2D connector frame_a for the steering on the plane. The rolling motion of the wheel can be actuated by the 1D connector flange_a.

In addition there is an input dynamicLoad for a dynamic component of the normal load.

Connectors:

  • frame_a (Frame) Coordinate system fixed to the component with one cut-force and cut-torque
  • flange_a (Rotational.Flange) Flange for the rolling motion
  • dynamicLoad (Blocks.RealInput) Input for the dynamic component of the normal load (must be connected)

Terminology:

  • Adhesion refers to the peak of the traction curve, where the slip is such that the maximum amount of traction is generated.
  • Sliding velocity refers to the velocity at which the traction curve saturates and stays constant with increased slip velocity.
source
Multibody.PlanarMechanics.limit_S_formMethod
limit_S_form(x_min, x_max, y_min, y_max, x)

Returns a S-shaped transition

A smooth transition between points (x_min, y_min) and (x_max, y_max). The transition is done in such a way that the function's 1st derivative is continuous for all x. The higher derivatives are discontinuous at input points.

x_min = -0.4
x_max = 0.6
y_max = 1.4
y_min = 1.2

julia> plot(x->Multibody.PlanarMechanics.limit_S_form(x_min, x_max, y_min, y_max, x), -1, 1, legend=false)
         ┌────────────────────────────────────────┐ 
   1.406 │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⡇⠀⠀⠀⠀⠀⠀⠀⠀⡠⠔⠒⠒⠒⠒⠒⠒⠒⠂⠀│ 
         │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⡇⠀⠀⠀⠀⠀⠀⢠⠊⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
         │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⡇⠀⠀⠀⠀⠀⡴⠁⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
         │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⡇⠀⠀⠀⠀⡰⠁⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
         │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⡇⠀⠀⠀⡜⠁⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
         │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⡇⠀⠀⡰⠁⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
         │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⡇⠀⢰⠁⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
         │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⡇⢠⠃⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
         │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⣧⠃⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
         │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⢠⡏⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
         │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⢠⠃⡇⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
         │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⢀⠇⠀⡇⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
         │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⡠⠃⠀⠀⡇⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
         │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⢀⡔⠁⠀⠀⠀⡇⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
   1.194 │⠀⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⠖⠉⠀⠀⠀⠀⠀⡇⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
         └────────────────────────────────────────┘ 
         ⠀-1.06⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀1.06⠀ 
source
Multibody.PlanarMechanics.limit_S_tripleMethod
limit_S_triple(x_max, x_sat, y_max, y_sat, x)

Returns a point-symmetric Triple S-Function

A point symmetric interpolation between points (0, 0), (x_max, y_max) and (x_sat, y_sat), provided x_max < x_sat. The approximation is done in such a way that the function's 1st derivative is zero at points (x_max, y_max) and (x_sat, y_sat). Thus, the function's 1st derivative is continuous for all x. The higher derivatives are discontinuous at these points.

x_max = 0.2
x_sat = 0.5
y_max = 1.4
y_sat = 1.2

plot(x->Multibody.PlanarMechanics.limit_S_triple(x_max, x_sat, y_max, y_sat, x), -1, 1)
vline!([x_max x_sat], label=["x_max" "x_sat"])

            ┌────────────────────────────────────────┐ 
    1.48385 │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⡇⠀⢀⡔⠢⠤⣀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
            │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⡇⠀⡜⠀⠀⠀⠈⠉⠒⠒⠒⠒⠒⠒⠒⠒⠒⠒⠂⠀│ 
            │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⡇⢠⠃⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
            │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⡇⡜⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
            │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⣇⠇⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
            │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⣿⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
            │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⡇⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
            │⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⢤⡧⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤│ 
            │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⢸⡇⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
            │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⡇⡇⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
            │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⢰⠁⡇⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
            │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⡜⠀⡇⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
            │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⢠⠃⠀⡇⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
            │⠀⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⠤⣀⡀⠀⠀⠀⡜⠀⠀⡇⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
   -1.48377 │⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠈⠒⠦⠼⠁⠀⠀⡇⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀│ 
            └────────────────────────────────────────┘ 
            ⠀-1.06⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀⠀1.06⠀ 
source