Joints and body-joint systems

For systems consisting of one or more rigid bodies, joints are used to specify the degrees of freedom permitted for the body. Even for a single rigid body, the body is assumed to be connected by a joint with the inertial coordinate system.

In three dimensions, there are several different classes of joint:

  • RevoluteJoint, which rotates about an axis and has only one degree of freedom
  • PrismaticJoint, which slides along one axis and has only one degree of freedom
  • HelicalJoint, which rotates about and slides along one axis (two degrees of freedom)
  • SphericalJoint, which rotates freely about one point (three degrees of freedom)
  • FreeJoint, which can move in any manner (six degrees of freedom)

However, in two spatial dimensions, there are only two

  • RevoluteJoint (one degree of freedom: rotation)
  • FreeJoint2d (three degrees of freedom: rotation, two translation)
using RigidBodyTools
using Plots

A joint serves as a connection between two bodies; one of the bodies is the parent and the other is the child. It is also common for a body to be connected to the inertial coordinate system, in which case the inertial system is the parent and the body is the child. The user must specify the id of the parent body and the child body. The id of the inertial system is 0.

Before we discuss how a joint is specified, it is important to understand that a joint is basically just an intermediate MotionTransform from the parent body's system to the child body's system.

That is, to construct the transform from body P to body C, we would compose it as follows

\[{}^C X_{P} = {}^{C}X_{J(C)} {}^{J(C)}X_{J(P)} {}^{J(P)}X_{P}\]

The transform in the middle is the joint transform and is the only one of these that can vary in time. It maps from one coordinate system attached (rididly) to the parent body to another coordinate system attached (rigidly) to the child body.

The degrees of freedom of the joint constrain the behavior of this joint transform. Below, we show how joints are constructed and used.

Joint construction generalities

The user must specify where the joint is located on each body, relative to the origin of the body's coordinate system, and what orientation the joint takes with respect to the body's coordinate system. These are specified with MotionTransforms, transforming from each body's coordinate system to the joint's coordinate system on that body. This transform is invariant – it never changes.

Also, the user must specify the behavior of each of the degrees of freedom of a joint, using the tools we discussed in the previous page.

The basic signature is

Joint(joint_type,parent_body_id,Xp_to_jp,child_body_id,Xc_to_jc,doflist)

However, there is a specialized signature if you simply wish to place a body in some stationary configuration X:

Joint(X,body_id)

and if there is only one body and it is stationary, then

Joint(X)

will do.

Example

Let's see a 2d example. Suppose we have two bodies, 1 and 2. Body 1 is to be connected to the inertial coordinate system, and prescribed with motion that causes it to oscillate rotationally (pitch) about a point located at $(-1,0)$ and in the body's coordinate system, and this pitch axis can oscillate up and down (heave).

Body 2 is to be connected by a hinge to body 1, and this hinge's angle will also oscillate. We will set the hinge to be located at $(1.02,0)$ on body 1 and $(-1.02,0)$ on body 2.

Joint from inertial system to body 1

First, let's construct the joint from the inertial system to body 1. This should be a FreeJoint2d, since motion is prescribed in two of the three degrees of freedom (as well as the third one, with zero velocity). We can assume that the joint is attached to the origin of the parent (the inertial system). On the child (body 1), the joint is to be at [-1,0].

pid = 0
Xp_to_jp = MotionTransform([0,0],0)
cid = 1
Xc_to_jc = MotionTransform([-1,0],0)
2d motion transform, x = [-1.0, 0.0], R = [1.0 -0.0; 0.0 1.0]

For the rotational and the y degrees of freedom, we need oscillatory motion. For the rotational motion, let's set the amplitude to $\pi/4$ and the angular frequency to $\Omega = 2\pi$, but set the phase and mean velocity both to zero.

Ar = π/4
Ω = 2π
ϕr = 0.0
vel = 0.0
kr = OscillatoryDOF(Ar,Ω,ϕr,vel)
Oscillatory kinematics (amplitude = 0.7853981633974483, ang freq = 6.283185307179586, phase = 0.0, mean velocity = 0.0)

For the plunging, we will set an amplitude of 1 and a phase lag of $\pi/2$, but keep the same frequency as the pitching.

Ay = 1
ϕy = -π/2
ky = OscillatoryDOF(Ay,Ω,ϕy,vel)
Oscillatory kinematics (amplitude = 1.0, ang freq = 6.283185307179586, phase = -1.5707963267948966, mean velocity = 0.0)

The x degree of freedom is simply constant velocity, set to 0, to ensure it does not move in the $x$ direction.

kx = ConstantVelocityDOF(0)
Constant velocity kinematics (velocity = 0.0)

We put these together into a vector, to pass along to the joint constructor. The ordering of these in the vector is important. It must be [rotational, x, y].

dofs = [kr,kx,ky];

Now set the joint

joint1 = Joint(FreeJoint2d,pid,Xp_to_jp,cid,Xc_to_jc,dofs)
Joint of dimension 2 and type FreeJoint2d
   Constrained dofs = [1, 2, 3]
   Exogenous dofs = Int64[]
   Unconstrained dofs = Int64[]

Note that this joint has three constrained degrees of freedom, no exogenous degrees of freedom, and no unconstrained degrees of freedom. In a later example, we will change this.

Joint from body 1 to body 2

This joint is a RevoluteJoint. First set the joint locations on each body.

pid = 1
Xp_to_jp = MotionTransform([1.02,0],0)
cid = 2
Xc_to_jc = MotionTransform([-1.02,0],0)
2d motion transform, x = [-1.02, 0.0], R = [1.0 -0.0; 0.0 1.0]

Now set its single degree of freedom (rotation) to have oscillatory kinematics. We will set its amplitude the same as before, but give it a phase lag

Ar = π/4
Ω = 2π
ϕr = -π/4
kr = OscillatoryDOF(Ar,Ω,ϕr,vel)
Oscillatory kinematics (amplitude = 0.7853981633974483, ang freq = 6.283185307179586, phase = -0.7853981633974483, mean velocity = 0.0)

Put it in a one-element vector.

dofs = [kr];

and construct the joint

joint2 = Joint(RevoluteJoint,pid,Xp_to_jp,cid,Xc_to_jc,dofs)
Joint of dimension 2 and type RevoluteJoint
   Constrained dofs = [1]
   Exogenous dofs = Int64[]
   Unconstrained dofs = Int64[]

Group the two joints together into a vector. It doesn't matter what order this vector is in, since the connectivity will be figured out any way it is ordered, but it numbers the joints by the order they are provided here.

joints = [joint1,joint2];

Assembling the joints and bodies

The joints and bodies comprise an overall RigidBodyMotion system. When this system is constructed, all of the connectivities are determined (or missing connectivities are revealed). The construction requires that we have set up the bodies themselves, so let's do that first. We will make both body 1 and body 2 an ellipse of aspect ratio 5. Note that ordering of bodies matters here, because the first in the list is interpreted as body 1, etc.

b1 = Ellipse(1.0,0.2,0.02)
b2 = Ellipse(1.0,0.2,0.02)
bodies = BodyList([b1,b2])
BodyList(Body[Elliptical body with 208 points and semi-axes (1.0,0.2)
   Current position: (0.0,0.0)
   Current angle (rad): 0.0
, Elliptical body with 208 points and semi-axes (1.0,0.2)
   Current position: (0.0,0.0)
   Current angle (rad): 0.0
])

Now we can construct the system

ls = RigidBodyMotion(joints,bodies)
1 linked system(s) of bodies
   2 bodies
   2 joints

Before we proceed, it is useful to demonstrate some of the tools we have to probe the connectivity of the system. For example, to find the parent joint of body 1, we use

parent_joint_of_body(1,ls)
1

This returns 1, since we have connected body 1 to joint 1. How about the child joint of body 1? We expect it to be 2. Since there might be more than one child, this returns a vector:

child_joints_of_body(1,ls)
1-element Vector{Int64}:
 2

We can also check the body connectivity of joints. This can be very useful for more complicated systems in which the joint numbering is less clear. The parent body of joint 1

parent_body_of_joint(1,ls)
0

This returns 0 since we have connected joint 1 to the inertial system. The child body of joint 2:

child_body_of_joint(2,ls)
2

The system state vector

A key concept in advancing, plotting, and doing further analysis of this system of joints and bodies is the state vector, $x$. This state vector has entries for the position of every degree of freedom of all of the joints. It also may have further entries for other quantities that need to be advanced, but for this example, there are no other entries.

There are two functions that are useful for constructing the state vector. The first is zero_motion_state, which simply creates a vector of zeros of the correct size.

zero_motion_state(bodies,ls)
4-element Vector{Float64}:
 0.0
 0.0
 0.0
 0.0

The second is init_motion_state, which fills in initial position values for any degrees of freedom that have been prescribed.

x = init_motion_state(bodies,ls)
4-element Vector{Float64}:
 0.0
 0.0
 1.0
 0.5553603672697958

Note that neither of these functions has any mutating effect on the arguments (bodies and ls).

Also, it is always possible for the user to modify the entries in the state vector after this function is called. In general, it would be difficult to determine which entry is which in this state vector, so we can use a special function for this. For example, to get access to just the part of the state vector for the positions of joint 1,

jid = 1
x1 = position_vector(x,ls,jid)
3-element view(::Vector{Float64}, [1, 2, 3]) with eltype Float64:
 0.0
 0.0
 1.0

This is a view on the overall state vector. This, if you decide to change an entry of x1, this, in turn, would change the correct entry in x.

We can use the system state vector to put the bodies in their proper places, using the joint positions in x.

update_body!(bodies,x,ls)
BodyList(Body[Elliptical body with 208 points and semi-axes (1.0,0.2)
   Current position: (1.0,1.0)
   Current angle (rad): 0.0
, Elliptical body with 208 points and semi-axes (1.0,0.2)
   Current position: (2.8867047018089242,1.5377945331279446)
   Current angle (rad): 0.5553603672697958
])

Let's plot this just to check

plot(bodies,xlims=(-4,4),ylims=(-4,4))
Example block output

Advancing the state vector

Once the initial state vector is constructed, then the system can be advanced in time. In this example, there are no exogenous or unconstrained degrees of freedom that require extra input, so the system is closed as it is. To advance the system, we need to solve the system of equations $\frac{\mathrm{d}x}{\mathrm{d}t} = f(x,t)$

The function $f(x,t)$ describing the rate of change of $x$ is given by the function motion_rhs!. This function mutates its first argument, the rate-of-change vector dxdt, which can then be used to update the state. The system and bodies are passed in as a tuple, followed by time.

Using a simple forward Euler method, the state vector can be advanced as follows

t0, x0 = 0.0, init_motion_state(bodies,ls)
dxdt = zero(x0)
x = copy(x0)
dt, tmax = 0.01, 4.0
for t in t0:dt:t0+tmax
  motion_rhs!(dxdt,x,(ls,bodies),t)
  global x += dxdt*dt
end

Now that we know how to advance the state vector, let's create a macro that can be used to make a movie of the evolving system.

macro animate_motion(b,m,dt,tmax,xlim,ylim)
    return esc(quote
            bc = deepcopy($b)
            t0, x0 = 0.0, init_motion_state(bc,$m)
            dxdt = zero(x0)
            x = copy(x0)

            @gif for t in t0:$dt:t0+$tmax
                motion_rhs!(dxdt,x,($m,bc),t)
                global x += dxdt*$dt
                update_body!(bc,x,$m)
                plot(bc,xlims=$xlim,ylims=$ylim)
            end every 5
        end)
end
@animate_motion (macro with 1 method)

Let's use it here

@animate_motion bodies ls 0.01 4 (-4,4) (-4,4)
Example block output

Joint functions

RigidBodyTools.JointType
Joint(jtype::AbstractJointType,parent_id,Xp_to_j::MotionTransform,child_id,Xch_to_j::MotionTransform,
        dofs::Vector{AbstractDOFKinematics};[params=Dict()])

Construct a joint of type jtype, connecting parent body of id parent_id to child body of id child_id. The placement of the joint on the bodies is given by Xp_to_j and Xch_to_j, the transforms from the parent and child coordinate systems to the joint system, respectively. Each of the degrees of freedom for the joint is specified with dofs, a vector of AbstractDOFKinematics. Any parameters required by the joint can be passed along in the optional params dictionary.

source
Joint(X::MotionTransform,bid::Int)

Construct a joint that simply places the body with ID bid rigidly in the configuration given by X.

source
Joint(X::MotionTransform)

For a problem with a single body, construct a joint that simply places the body rigidly in the configuration given by X.

source
RigidBodyTools.zero_jointFunction
zero_joint(joint::Joint[;dimfcn=position_and_vel_dimension])

Create a vector of zeros for different aspects of the joint state, based on the argument dimfcn. By default, it uses position_and_vel_dimension and creates a zero vector sized according to the the position of the joint and the parts of the joint velocity that must be advanced (from acceleration). Alternatively, one can use position_dimension, constrained_dimension, unconstrained_dimension, or exogenous_dimension.

source
zero_joint(ls::RigidBodyMotion[;dimfcn=position_and_vel_dimension])

Create a vector of zeros for some aspect of the state of the linked system(s) ls, based on the argument dimfcn. By default, it uses position_and_vel_dimension and creates a zero vector sized according to the state of the joint. Alternatively, one can use position_dimension, constrained_dimension, unconstrained_dimension, or exogenous_dimension.

source
RigidBodyTools.init_jointFunction
init_joint(joint::Joint[;tinit=0.0])

Create an initial state vector for a joint. It initializes the joint's constrained degrees of freedom with their kinematics, evaluated at time tinit (equal to zero, by default). Other degrees of freedom (exogenous, unconstrained) are initialized to zero, so they can be set manually.

source

System and state functions

RigidBodyTools.RigidBodyMotionType
RigidBodyMotion

Type containing the connectivities and motions of rigid bodies, linked to the inertial system and possibly to each other, via joints. The basic constructor is RigidBodyMotion(joints::Vector{Joint},nbody::Int), in which joints contains a vector of joints of Joint type, each specifying the connection between a parent and a child body. (The parent may be the inertial coordinate system.)

source
RigidBodyTools.init_motion_stateFunction
init_motion_state(bl::BodyList,ls::RigidBodyMotion[;tinit = 0.0])

Initialize the global linked system state vector, using the prescribed motions for constrained degrees of freedom to initialize the position components (evaluated at tinit, which by default is 0). The other degrees of freedom are initialized to zero, and can be set manually.

source
Base.viewMethod
view(q::AbstractVector,ls::RigidBodyMotion,jid::Int[;dimfcn=position_dimension]) -> SubArray

Provide a view of the range of values in vector q corresponding to the position of the joint with index jid in a RigidBodyMotion ls. The optional argument dimfcn can be set to position_dimension, constrained_dimension, unconstrained_dimension, or exogenous_dimension.

source
RigidBodyTools.position_vectorFunction
position_vector(x::AbstractVector,ls::RigidBodyMotion)

Returns a view of the global state vector for a linked system containing only the position.

source
position_vector(x::AbstractVector,ls::RigidBodyMotion,jid::Int)

Returns a view of the global state vector for a linked system containing only the position of joint jid.

source
RigidBodyTools.velocity_vectorFunction
velocity_vector(x::AbstractVector,ls::RigidBodyMotion)

Returns a view of the global state vector for a linked system containing only the velocity.

source
velocity_vector(x::AbstractVector,ls::RigidBodyMotion,jid::Int)

Returns a view of the global state vector for a linked system containing only the velocity of joint jid.

source
RigidBodyTools.deformation_vectorFunction
deformation_vector(x::AbstractVector,ls::RigidBodyMotion,bid::Int)

Returns a view of the global state vector for a linked system containing only the body surface positions of the body with id bid.

source
RigidBodyTools.exogenous_position_vectorFunction
exogenous_position_vector(x::AbstractVector,ls::RigidBodyMotion,jid::Int)

Returns a view of the exogenous dof position(s), if any, of joint jid in the global state vector x.

source
RigidBodyTools.exogenous_velocity_vectorFunction
exogenous_velocity_vector(x::AbstractVector,ls::RigidBodyMotion,jid::Int)

Returns a view of the exogenous dof position(s), if any, of joint jid in the global state vector x.

source
RigidBodyTools.body_transformsFunction
body_transforms(x::AbstractVector,ls::RigidBodyMotion) -> MotionTransformList

Parse the overall state vector x into the individual joints and construct the inertial system-to-body transforms for every body. Return these transforms in a MotionTransformList.

source
RigidBodyTools.motion_transform_from_A_to_BFunction
motion_transform_from_A_to_B(tl::MotionTransformList,bodyidA::Int,bodyidB::Int) -> MotionTransform

Returns a motion transform mapping from the coordinate system of body bodyidA to body bodyidB. Either of these bodies might be 0.

source
RigidBodyTools.force_transform_from_A_to_BFunction
force_transform_from_A_to_B(tl::MotionTransformList,bodyidA::Int,bodyidB::Int) -> ForceTransform

Returns a force transform mapping from the coordinate system of body bodyidA to body bodyidB. Either of these bodies might be 0.

source
RigidBodyTools.body_velocitiesFunction
body_velocities(x::AbstractVector,t::Real,ls::RigidBodyMotion) -> PluckerMotionList

Compute the velocities of bodies for the rigid body system ls, expressing each in its own coordinate system. To carry this out, the function evaluates velocities of dofs with prescribed kinematics at time t and and obtains the remaining free dofs (exogenous and unconstrained) from the state vector x.

source
RigidBodyTools.motion_rhs!Function
motion_rhs!(dxdt::AbstractVector,x::AbstractVector,p::Tuple{RigidBodyMotion,BodyList},t::Real)

Sets the right-hand side vector dxdt (mutating) for linked system ls of bodies bl, using the current state vector x, the current time t.

source
RigidBodyTools.update_exogenous!Function
update_exogenous!(ls::RigidBodyMotion,a_edof::AbstractVector)

Mutates the exogenous buffer of ls with the supplied vector of exogenous accelerations a_edof. This function is useful for supplying time-varying exogenous values to the integrator from an outer loop.

source
RigidBodyTools.maxvelocityFunction
maxvelocity(b::Union{Body,BodyList},x::AbstractVector,m::RigidBodyMotion[,tmax=10,dt=0.05])

Search through the given motion state vector x and motion m applied to body b and return (umax,i,t,bid), the maximum velocity magnitude, the global index of the body point where it occurs, the time at which it occurs, and the body on which it occurs.

source
RigidBodyTools.is_system_in_relative_motionFunction
is_system_in_relative_motion(lsid::Int,ls::RigidBodyMotion) -> Bool

Returns true if the linked system with ID lsid is in relative motion, i.e., if one or more of the joints (not connected to the inertial system) returns true for the function ismoving(joint).

source
RigidBodyTools.rebase_from_inertial_to_referenceFunction
rebase_from_inertial_to_reference(Xi_to_A::MotionTransform,x::AbstractVector,m::RigidBodyMotion,reference_body::Int)

If Xi_to_A represents a motion transform from the inertial coordinates to some other coordinates A, such as that of a body, then this function returns a motion transform from the reference body coordinates to coordinates A. It uses the current joint state vector x to construct the transform list of the system m.

source

Joint types

RigidBodyTools.HelicalJointType
HelicalJoint <: AbstractJointType

A 3d joint with one rotational (angle about z axis) degree of freedom, and coupled translational motion along the z axis based on pitch.

source
RigidBodyTools.SphericalJointType
SphericalJoint <: AbstractJointType

A 3d joint with three rotational degrees of freedom. It uses a quaternion to define its orientation, so it has four position coordinates.

source
RigidBodyTools.FreeJointType
FreeJoint <: AbstractJointType

A 3d joint with all six degrees of freedom. It uses a quaternion to define its orientation, so it has seven position coordinates.

source

This page was generated using Literate.jl.