Joints
Index
RigidBodyDynamics.Fixed
RigidBodyDynamics.Joint
RigidBodyDynamics.JointType
RigidBodyDynamics.Planar
RigidBodyDynamics.Planar
RigidBodyDynamics.Prismatic
RigidBodyDynamics.Prismatic
RigidBodyDynamics.QuaternionFloating
RigidBodyDynamics.QuaternionSpherical
RigidBodyDynamics.Revolute
RigidBodyDynamics.Revolute
RigidBodyDynamics.SPQuatFloating
RigidBodyDynamics.bias_acceleration
RigidBodyDynamics.configuration_derivative_to_velocity!
RigidBodyDynamics.configuration_derivative_to_velocity_adjoint!
RigidBodyDynamics.configuration_derivative_to_velocity_jacobian
RigidBodyDynamics.constraint_wrench_subspace
RigidBodyDynamics.effort_bounds
RigidBodyDynamics.global_coordinates!
RigidBodyDynamics.has_fixed_subspaces
RigidBodyDynamics.isfloating
RigidBodyDynamics.joint_spatial_acceleration
RigidBodyDynamics.joint_torque!
RigidBodyDynamics.joint_transform
RigidBodyDynamics.joint_twist
RigidBodyDynamics.local_coordinates!
RigidBodyDynamics.motion_subspace
RigidBodyDynamics.normalize_configuration!
RigidBodyDynamics.num_constraints
RigidBodyDynamics.num_positions
RigidBodyDynamics.num_velocities
RigidBodyDynamics.position_bounds
RigidBodyDynamics.principal_value!
RigidBodyDynamics.rand_configuration!
RigidBodyDynamics.velocity_bounds
RigidBodyDynamics.velocity_to_configuration_derivative!
RigidBodyDynamics.velocity_to_configuration_derivative_jacobian
RigidBodyDynamics.zero_configuration!
The Joint
type
RigidBodyDynamics.Joint
— Type.struct Joint{T, JT<:JointType{T}}
A joint represents a kinematic restriction of the relative twist between two rigid bodies to a linear subspace of dimension $k$.
A joint has a direction. The rigid body before the joint is called the joint's predecessor, and the rigid body after the joint is its successor.
The state related to the joint is parameterized by two sets of variables, namely
- a vector $q \in \mathcal{Q}$, parameterizing the relative homogeneous transform.
- a vector $v \in \mathbb{R}^k$, parameterizing the relative twist.
The twist of the successor with respect to the predecessor is a linear function of $v$.
For some joint types (notably those using a redundant representation of relative orientation, such as a unit quaternion), $\dot{q}$, the time derivative of $q$, may not be the same as $v$. However, an invertible linear transformation exists between $\dot{q}$ and $v$.
See also:
- Definition 2.9 in Duindam, "Port-Based Modeling and Control for Efficient Bipedal Walking Robots", 2006.
- Section 4.4 of Featherstone, "Rigid Body Dynamics Algorithms", 2008.
Functions
RigidBodyDynamics.bias_acceleration
— Method.bias_acceleration(joint, q, v)
Return the acceleration of the joint's successor with respect to its predecessor in configuration $q$ and at velocity $v$, when the joint acceleration $\dot{v}$ is zero.
configuration_derivative_to_velocity!(v, joint, q, q̇)
Compute joint velocity vector $v$ given the joint configuration vector $q$ and its time derivative $\dot{q}$ (in place).
Note that this mapping is linear.
See also velocity_to_configuration_derivative!
, the inverse mapping.
configuration_derivative_to_velocity_adjoint!(fq, joint, q, fv)
Given a linear function
where $v$ is the joint velocity vector, return a vector $f_q$ such that
Note: since $v$ is a linear function of $\dot{q}$ (see configuration_derivative_to_velocity!
), we can write $v = J_{\dot{q} \rightarrow v} \dot{q}$, so
so $f_q = J_{\dot{q} \rightarrow v}^{*} f_v$.
To compute $J_{\dot{q} \rightarrow v}$ see configuration_derivative_to_velocity_jacobian
.
constraint_wrench_subspace(joint, joint_transform)
Return a basis for the constraint wrench subspace of the joint, where joint_transform
is the transform from the frame after the joint to the frame before the joint.
The constraint wrench subspace is a $6 \times (6 - k)$ matrix, where $k$ is the dimension of the velocity vector $v$, that maps a vector of Lagrange multipliers $\lambda$ to the constraint wrench exerted across the joint onto its successor.
The constraint wrench subspace is orthogonal to the motion subspace.
RigidBodyDynamics.effort_bounds
— Method.effort_bounds(joint)
Return a Vector{Bounds{T}}
giving the upper and lower bounds of the effort for joint
RigidBodyDynamics.global_coordinates!
— Method.global_coordinates!(q, joint, q0, ϕ)
Compute the global parameterization of the joint's configuration, $q$, given a 'base' orientation $q_0$ and a vector of local coordinates $ϕ$ centered around $q_0$.
See also local_coordinates!
.
RigidBodyDynamics.has_fixed_subspaces
— Method.has_fixed_subspaces(joint)
Whether the joint's motion subspace and constraint wrench subspace depend on $q$.
RigidBodyDynamics.isfloating
— Method.isfloating(joint)
Whether the joint is a floating joint, i.e., whether it imposes no constraints on the relative motions of its successor and predecessor bodies.
RigidBodyDynamics.joint_transform
— Method.joint_transform(joint, q)
Return a Transform3D
representing the homogeneous transform from the frame after the joint to the frame before the joint for joint configuration vector $q$.
RigidBodyDynamics.local_coordinates!
— Method.local_coordinates!(ϕ, ϕ̇, joint, q0, q, v)
Compute a vector of local coordinates $\phi$ around configuration $q_0$ corresponding to configuration $q$ (in place). Also compute the time derivative $\dot{\phi}$ of $\phi$ given the joint velocity vector $v$.
The local coordinate vector $\phi$ must be zero if and only if $q = q_0$.
For revolute or prismatic joint types, the local coordinates can just be $\phi = q - q_0$, but for joint types with configuration vectors that are restricted to a manifold (e.g. when unit quaternions are used to represent orientation), elementwise subtraction may not make sense. For such joints, exponential coordinates could be used as the local coordinate vector $\phi$.
See also global_coordinates!
.
RigidBodyDynamics.motion_subspace
— Method.motion_subspace(joint, q)
Return a basis for the motion subspace of the joint in configuration $q$.
The motion subspace basis is a $6 \times k$ matrix, where $k$ is the dimension of the velocity vector $v$, that maps $v$ to the twist of the joint's successor with respect to its predecessor. The returned motion subspace is expressed in the frame after the joint, which is attached to the joint's successor.
normalize_configuration!(q, joint)
Renormalize the configuration vector $q$ associated with joint
so that it lies on the joint's configuration manifold.
RigidBodyDynamics.num_constraints
— Method.num_constraints(joint)
Return the number of constraints imposed on the relative twist between the joint's predecessor and successor
RigidBodyDynamics.num_positions
— Method.num_positions(joint)
Return the length of the configuration vector of joint
.
RigidBodyDynamics.num_velocities
— Method.num_velocities(joint)
Return the length of the velocity vector of joint
.
RigidBodyDynamics.position_bounds
— Method.position_bounds(joint)
Return a Vector{Bounds{T}}
giving the upper and lower bounds of the configuration for joint
RigidBodyDynamics.principal_value!
— Method.principal_value!(q, joint)
Applies the principalvalue functions from [Rotations.jl](https://github.com/FugroRoames/Rotations.jl/blob/d080990517f89b56c37962ad53a7fd24bd94b9f7/src/principalvalue.jl) to joint angles. This currently only applies to SPQuatFloating
joints.
RigidBodyDynamics.rand_configuration!
— Method.rand_configuration!(q, joint)
Set $q$ to a random configuration. The distribution used depends on the joint type.
RigidBodyDynamics.velocity_bounds
— Method.velocity_bounds(joint)
Return a Vector{Bounds{T}}
giving the upper and lower bounds of the velocity for joint
velocity_to_configuration_derivative!(q̇, joint, q, v)
Compute the time derivative $\dot{q}$ of the joint configuration vector $q$ given $q$ and the joint velocity vector $v$ (in place).
Note that this mapping is linear.
See also configuration_derivative_to_velocity!
, the inverse mapping.
RigidBodyDynamics.zero_configuration!
— Method.zero_configuration!(q, joint)
Set $q$ to the 'zero' configuration, corresponding to an identity joint transform.
configuration_derivative_to_velocity_jacobian(joint, q)
Compute the jacobian $J_{\dot{q} \rightarrow v}$ which maps joint configuration derivative to velocity for the given joint:
joint_spatial_acceleration(joint, q, v, vd)
Return the spatial acceleration of joint
's successor with respect to its predecessor, expressed in the frame after the joint.
RigidBodyDynamics.joint_torque!
— Method.joint_torque!(τ, joint, q, joint_wrench)
Given the wrench exerted across the joint on the joint's successor, compute the vector of joint torques $\tau$ (in place), in configuration q
.
RigidBodyDynamics.joint_twist
— Method.joint_twist(joint, q, v)
Return the twist of joint
's successor with respect to its predecessor, expressed in the frame after the joint.
Note that this is the same as Twist(motion_subspace(joint, q), v)
.
velocity_to_configuration_derivative_jacobian(joint, q)
Compute the jacobian $J_{v \rightarrow \dot{q}}$ which maps joint velocity to configuration derivative for the given joint:
JointType
s
RigidBodyDynamics.JointType
— Type.abstract type JointType
The abstract supertype of all concrete joint types.
Fixed
RigidBodyDynamics.Fixed
— Type.struct Fixed{T} <: JointType{T}
The Fixed
joint type is a degenerate joint type, in the sense that it allows no motion between its predecessor and successor rigid bodies.
Revolute
RigidBodyDynamics.Revolute
— Type.struct Revolute{T} <: RigidBodyDynamics.OneDegreeOfFreedomFixedAxis{T}
A Revolute
joint type allows rotation about a fixed axis.
RigidBodyDynamics.Revolute
— Method.Revolute(axis)
Construct a new Revolute
joint type, allowing rotation about axis
(expressed in the frame before the joint).
Prismatic
RigidBodyDynamics.Prismatic
— Type.struct Prismatic{T} <: RigidBodyDynamics.OneDegreeOfFreedomFixedAxis{T}
A Prismatic
joint type allows translation along a fixed axis.
RigidBodyDynamics.Prismatic
— Method.Construct a new Prismatic
joint type, allowing translation along axis
(expressed in the frame before the joint).
Planar
RigidBodyDynamics.Planar
— Type.struct Planar{T} <: JointType{T}
The Planar
joint type allows translation along two orthogonal vectors, referred to as $x$ and $y$, as well as rotation about an axis $z = x \times y$.
The components of the 3-dimensional configuration vector $q$ associated with a Planar
joint are the $x$- and $y$-coordinates of the translation, and the angle of rotation $\theta$ about $z$, in that order.
The components of the 3-dimension velocity vector $v$ associated with a Planar
joint are the $x$- and $y$-coordinates of the linear part of the joint twist, expressed in the frame after the joint, followed by the $z$-component of the angular part of this joint twist.
For the Planar
joint type, $v \neq \dot{q}$! Although the angular parts of $v$ and $\dot{q}$ are the same, their linear parts differ. The linear part of $v$ is the linear part of $\dot{q}$, rotated to the frame after the joint. This parameterization was chosen to allow the translational component of the joint transform to be independent of the rotation angle $\theta$ (i.e., the rotation is applied after the translation), while still retaining a constant motion subspace expressed in the frame after the joint.
RigidBodyDynamics.Planar
— Method.Planar(x_axis, y_axis)
Construct a new Planar
joint type with the $xy$-plane in which translation is allowed defined by 3-vectors x
and y
expressed in the frame before the joint.
QuaternionSpherical
struct QuaternionSpherical{T} <: JointType{T}
The QuaternionSpherical
joint type allows rotation in any direction. It is an implementation of a ball-and-socket joint.
The 4-dimensional configuration vector $q$ associated with a QuaternionSpherical
joint is the unit quaternion that describes the orientation of the frame after the joint with respect to the frame before the joint. In other words, it is the quaternion that can be used to rotate vectors from the frame after the joint to the frame before the joint.
The 3-dimensional velocity vector $v$ associated with a QuaternionSpherical
joint is the angular velocity of the frame after the joint with respect to the frame before the joint, expressed in the frame after the joint (body frame).
QuaternionFloating
struct QuaternionFloating{T} <: JointType{T}
A floating joint type that uses a unit quaternion representation for orientation.
Floating joints are 6-degree-of-freedom joints that are in a sense degenerate, as they impose no constraints on the relative motion between two bodies.
The full, 7-dimensional configuration vector of a QuaternionFloating
joint type consists of a unit quaternion representing the orientation that rotates vectors from the frame 'directly after' the joint to the frame 'directly before' it, and a 3D position vector representing the origin of the frame after the joint in the frame before the joint.
The 6-dimensional velocity vector of a QuaternionFloating
joint is the twist of the frame after the joint with respect to the frame before it, expressed in the frame after the joint.
SPQuatFloating
RigidBodyDynamics.SPQuatFloating
— Type.struct SPQuatFloating{T} <: JointType{T}
A floating joint type that uses a SPQuat representation for orientation.
Floating joints are 6-degree-of-freedom joints that are in a sense degenerate, as they impose no constraints on the relative motion between two bodies.
The 6-dimensional configuration vector of a SPQuatFloating
joint type consists of a SPQuat representing the orientation that rotates vectors from the frame 'directly after' the joint to the frame 'directly before' it, and a 3D position vector representing the origin of the frame after the joint in the frame before the joint.
The 6-dimensional velocity vector of a SPQuatFloating
joint is the twist of the frame after the joint with respect to the frame before it, expressed in the frame after the joint.